Repository: OpenDriveLab/ThinkTwice Branch: main Commit: e9cf2fc078f6 Files: 392 Total size: 24.2 MB Directory structure: gitextract_y09f2xlv/ ├── .github/ │ └── FUNDING.yml ├── .gitignore ├── LICENSE ├── README.md ├── agents/ │ ├── __init__.py │ ├── navigation/ │ │ ├── __init__.py │ │ ├── agent.py │ │ ├── basic_agent.py │ │ ├── behavior_agent.py │ │ ├── controller.py │ │ ├── global_route_planner.py │ │ ├── global_route_planner_dao.py │ │ ├── local_planner.py │ │ ├── local_planner_behavior.py │ │ ├── roaming_agent.py │ │ └── types_behavior.py │ └── tools/ │ ├── __init__.py │ └── misc.py ├── camera_calibration/ │ ├── README.md │ ├── calculate_distortion_parameters.py │ ├── collect_data_for_calibration.py │ └── undistort.py ├── dataset/ │ └── tools/ │ ├── generate_metadata.py │ └── generate_random_routes.py ├── docs/ │ ├── DATA_PREP.md │ ├── EVAL.md │ ├── INSTALL.md │ └── TRAIN.md ├── leaderboard/ │ ├── LICENSE │ ├── README.md │ ├── data/ │ │ ├── routes_for_evaluation/ │ │ │ ├── routes_longest6.xml │ │ │ └── routes_town05_long.xml │ │ ├── routes_for_open_loop_training/ │ │ │ ├── routes_town01_00.xml │ │ │ ├── routes_town01_01.xml │ │ │ ├── routes_town01_02.xml │ │ │ ├── routes_town01_03.xml │ │ │ ├── routes_town01_04.xml │ │ │ ├── routes_town01_05.xml │ │ │ ├── routes_town01_06.xml │ │ │ ├── routes_town01_07.xml │ │ │ ├── routes_town01_08.xml │ │ │ ├── routes_town01_09.xml │ │ │ ├── routes_town01_10.xml │ │ │ ├── routes_town01_11.xml │ │ │ ├── routes_town01_val.xml │ │ │ ├── routes_town02_00.xml │ │ │ ├── routes_town02_01.xml │ │ │ ├── routes_town02_02.xml │ │ │ ├── routes_town02_03.xml │ │ │ ├── routes_town02_04.xml │ │ │ ├── routes_town02_05.xml │ │ │ ├── routes_town02_06.xml │ │ │ ├── routes_town02_07.xml │ │ │ ├── routes_town02_08.xml │ │ │ ├── routes_town02_09.xml │ │ │ ├── routes_town02_10.xml │ │ │ ├── routes_town02_11.xml │ │ │ ├── routes_town02_val.xml │ │ │ ├── routes_town03_00.xml │ │ │ ├── routes_town03_01.xml │ │ │ ├── routes_town03_02.xml │ │ │ ├── routes_town03_03.xml │ │ │ ├── routes_town03_04.xml │ │ │ ├── routes_town03_05.xml │ │ │ ├── routes_town03_06.xml │ │ │ ├── routes_town03_07.xml │ │ │ ├── routes_town03_08.xml │ │ │ ├── routes_town03_09.xml │ │ │ ├── routes_town03_10.xml │ │ │ ├── routes_town03_11.xml │ │ │ ├── routes_town03_val.xml │ │ │ ├── routes_town04_00.xml │ │ │ ├── routes_town04_01.xml │ │ │ ├── routes_town04_02.xml │ │ │ ├── routes_town04_03.xml │ │ │ ├── routes_town04_04.xml │ │ │ ├── routes_town04_05.xml │ │ │ ├── routes_town04_06.xml │ │ │ ├── routes_town04_07.xml │ │ │ ├── routes_town04_08.xml │ │ │ ├── routes_town04_09.xml │ │ │ ├── routes_town04_10.xml │ │ │ ├── routes_town04_11.xml │ │ │ ├── routes_town04_val.xml │ │ │ ├── routes_town05_00.xml │ │ │ ├── routes_town05_01.xml │ │ │ ├── routes_town05_02.xml │ │ │ ├── routes_town05_03.xml │ │ │ ├── routes_town05_04.xml │ │ │ ├── routes_town05_05.xml │ │ │ ├── routes_town05_06.xml │ │ │ ├── routes_town05_07.xml │ │ │ ├── routes_town05_08.xml │ │ │ ├── routes_town05_09.xml │ │ │ ├── routes_town05_10.xml │ │ │ ├── routes_town05_11.xml │ │ │ ├── routes_town05_val.xml │ │ │ ├── routes_town06_00.xml │ │ │ ├── routes_town06_01.xml │ │ │ ├── routes_town06_02.xml │ │ │ ├── routes_town06_03.xml │ │ │ ├── routes_town06_04.xml │ │ │ ├── routes_town06_05.xml │ │ │ ├── routes_town06_06.xml │ │ │ ├── routes_town06_07.xml │ │ │ ├── routes_town06_08.xml │ │ │ ├── routes_town06_09.xml │ │ │ ├── routes_town06_10.xml │ │ │ ├── routes_town06_11.xml │ │ │ ├── routes_town06_val.xml │ │ │ ├── routes_town07_00.xml │ │ │ ├── routes_town07_01.xml │ │ │ ├── routes_town07_02.xml │ │ │ ├── routes_town07_03.xml │ │ │ ├── routes_town07_04.xml │ │ │ ├── routes_town07_05.xml │ │ │ ├── routes_town07_06.xml │ │ │ ├── routes_town07_07.xml │ │ │ ├── routes_town07_08.xml │ │ │ ├── routes_town07_09.xml │ │ │ ├── routes_town07_10.xml │ │ │ ├── routes_town07_11.xml │ │ │ ├── routes_town07_val.xml │ │ │ ├── routes_town10_00.xml │ │ │ ├── routes_town10_01.xml │ │ │ ├── routes_town10_02.xml │ │ │ ├── routes_town10_03.xml │ │ │ ├── routes_town10_04.xml │ │ │ ├── routes_town10_05.xml │ │ │ ├── routes_town10_06.xml │ │ │ ├── routes_town10_07.xml │ │ │ ├── routes_town10_08.xml │ │ │ ├── routes_town10_09.xml │ │ │ ├── routes_town10_10.xml │ │ │ ├── routes_town10_11.xml │ │ │ └── routes_town10_val.xml │ │ └── scenarios/ │ │ ├── all_towns_traffic_scenarios_no256.json │ │ └── longest6_eval_scenarios.json │ ├── leaderboard/ │ │ ├── __init__.py │ │ ├── autoagents/ │ │ │ ├── __init__.py │ │ │ ├── agent_wrapper.py │ │ │ ├── autonomous_agent.py │ │ │ ├── dummy_agent.py │ │ │ ├── human_agent.py │ │ │ ├── human_agent_config.txt │ │ │ ├── npc_agent.py │ │ │ └── ros_agent.py │ │ ├── envs/ │ │ │ ├── __init__.py │ │ │ └── sensor_interface.py │ │ ├── leaderboard_evaluator.py │ │ ├── scenarios/ │ │ │ ├── __init__.py │ │ │ ├── background_activity.py │ │ │ ├── master_scenario.py │ │ │ ├── route_scenario.py │ │ │ ├── scenario_manager.py │ │ │ └── scenarioatomics/ │ │ │ ├── __init__.py │ │ │ └── atomic_criteria.py │ │ └── utils/ │ │ ├── __init__.py │ │ ├── checkpoint_tools.py │ │ ├── result_writer.py │ │ ├── route_indexer.py │ │ ├── route_manipulation.py │ │ ├── route_parser.py │ │ └── statistics_manager.py │ ├── scripts/ │ │ ├── collect_data.sh │ │ ├── evaluation_longest6.sh │ │ └── evaluation_town05long.sh │ └── team_code/ │ ├── auto_pilot.py │ ├── base_agent.py │ ├── map_agent.py │ ├── pid_controller.py │ ├── planner.py │ ├── roach_ap_agent_data_collection.py │ ├── thinktwice_agent.py │ └── thinktwice_agent_old.py ├── open_loop_training/ │ ├── __init__.py │ ├── code/ │ │ ├── __init__.py │ │ ├── apis/ │ │ │ ├── __init__.py │ │ │ ├── mmdet_train.py │ │ │ └── train.py │ │ ├── core/ │ │ │ └── evaluation/ │ │ │ ├── __init__.py │ │ │ ├── epoch_hook.py │ │ │ ├── eval_hooks.py │ │ │ └── eval_tool.py │ │ ├── datasets/ │ │ │ ├── __init__.py │ │ │ ├── base_dataset.py │ │ │ ├── builder.py │ │ │ ├── carla_dataset.py │ │ │ ├── pipelines/ │ │ │ │ ├── __init__.py │ │ │ │ ├── formating.py │ │ │ │ ├── loading.py │ │ │ │ └── transform.py │ │ │ └── samplers/ │ │ │ ├── __init__.py │ │ │ ├── distributed_sampler.py │ │ │ ├── group_sampler.py │ │ │ └── sampler.py │ │ ├── encoder_decoder_framework.py │ │ ├── model_code/ │ │ │ ├── backbones/ │ │ │ │ ├── __init__.py │ │ │ │ ├── lidarnet.py │ │ │ │ └── lss.py │ │ │ └── dense_heads/ │ │ │ ├── __init__.py │ │ │ ├── multi_scale_deformable_attn_function.py │ │ │ ├── thinktwice_decoder.py │ │ │ └── utils.py │ │ └── utils.py │ ├── configs/ │ │ ├── _base_/ │ │ │ ├── default_runtime.py │ │ │ └── schedules/ │ │ │ ├── cosine.py │ │ │ ├── cyclic_20e.py │ │ │ ├── cyclic_40e.py │ │ │ ├── mmdet_schedule_1x.py │ │ │ ├── schedule_2x.py │ │ │ ├── schedule_3x.py │ │ │ ├── seg_cosine_150e.py │ │ │ ├── seg_cosine_200e.py │ │ │ └── seg_cosine_50e.py │ │ └── thinktwice.py │ ├── ops/ │ │ └── voxel_pooling/ │ │ ├── __init__.py │ │ ├── src/ │ │ │ ├── voxel_pooling_forward.cpp │ │ │ └── voxel_pooling_forward_cuda.cu │ │ └── voxel_pooling.py │ ├── setup.py │ └── train.py ├── roach/ │ ├── config/ │ │ └── config_agent.yaml │ ├── criteria/ │ │ ├── blocked.py │ │ ├── collision.py │ │ ├── encounter_light.py │ │ ├── outside_route_lane.py │ │ ├── route_deviation.py │ │ ├── run_red_light.py │ │ └── run_stop_sign.py │ ├── log/ │ │ └── ckpt_11833344.pth │ ├── models/ │ │ ├── distributions.py │ │ ├── ppo.py │ │ ├── ppo_buffer.py │ │ ├── ppo_policy.py │ │ ├── torch_layers.py │ │ └── torch_util.py │ ├── obs_manager/ │ │ ├── actor_state/ │ │ │ ├── control.py │ │ │ ├── route.py │ │ │ ├── speed.py │ │ │ └── velocity.py │ │ └── birdview/ │ │ ├── chauffeurnet.py │ │ ├── hdmap_generate.py │ │ └── maps/ │ │ ├── Town01.h5 │ │ ├── Town02.h5 │ │ ├── Town03.h5 │ │ ├── Town04.h5 │ │ ├── Town05.h5 │ │ ├── Town06.h5 │ │ ├── Town07.h5 │ │ └── Town10HD.h5 │ ├── rl_birdview_agent.py │ └── utils/ │ ├── config_utils.py │ ├── expert_noiser.py │ ├── rl_birdview_wrapper.py │ ├── traffic_light.py │ ├── transforms.py │ └── wandb_callback.py └── scenario_runner/ ├── CARLA_VER ├── Dockerfile ├── Docs/ │ ├── CHANGELOG.md │ ├── CODE_OF_CONDUCT.md │ ├── CONTRIBUTING.md │ ├── FAQ.md │ ├── agent_evaluation.md │ ├── coding_standard.md │ ├── creating_new_scenario.md │ ├── extra.css │ ├── getting_scenariorunner.md │ ├── getting_started.md │ ├── index.md │ ├── list_of_scenarios.md │ ├── metrics_module.md │ ├── openscenario_support.md │ ├── requirements.txt │ └── ros_agent.md ├── Jenkinsfile ├── LICENSE ├── README.md ├── manual_control.py ├── metrics_manager.py ├── mkdocs.yml ├── no_rendering_mode.py ├── requirements.txt ├── scenario_runner.py └── srunner/ ├── __init__.py ├── autoagents/ │ ├── __init__.py │ ├── agent_wrapper.py │ ├── autonomous_agent.py │ ├── dummy_agent.py │ ├── human_agent.py │ ├── npc_agent.py │ ├── ros_agent.py │ └── sensor_interface.py ├── data/ │ ├── all_towns_traffic_scenarios1_3_4.json │ ├── all_towns_traffic_scenarios1_3_4_8.json │ ├── no_scenarios.json │ ├── routes_debug.xml │ ├── routes_devtest.xml │ └── routes_training.xml ├── examples/ │ ├── CatalogExample.xosc │ ├── ChangeLane.xml │ ├── ChangingWeather.xosc │ ├── ControlLoss.xml │ ├── CutIn.xml │ ├── CyclistCrossing.xosc │ ├── FollowLeadingVehicle.xml │ ├── FollowLeadingVehicle.xosc │ ├── FreeRide.xml │ ├── LaneChangeSimple.xosc │ ├── LeadingVehicle.xml │ ├── NoSignalJunction.xml │ ├── ObjectCrossing.xml │ ├── OppositeDirection.xml │ ├── OscControllerExample.xosc │ ├── PedestrianCrossingFront.xosc │ ├── RunningRedLight.xml │ ├── SignalizedJunctionLeftTurn.xml │ ├── SignalizedJunctionRightTurn.xml │ ├── VehicleTurning.xml │ └── catalogs/ │ ├── ControllerCatalog.xosc │ ├── EnvironmentCatalog.xosc │ ├── ManeuverCatalog.xosc │ ├── MiscObjectCatalog.xosc │ ├── PedestrianCatalog.xosc │ └── VehicleCatalog.xosc ├── metrics/ │ ├── data/ │ │ ├── CriteriaFilter_criteria.json │ │ ├── DistanceBetweenVehicles_criteria.json │ │ └── DistanceToLaneCenter_criteria.json │ ├── examples/ │ │ ├── basic_metric.py │ │ ├── criteria_filter.py │ │ ├── distance_between_vehicles.py │ │ └── distance_to_lane_center.py │ └── tools/ │ ├── metrics_log.py │ └── metrics_parser.py ├── openscenario/ │ ├── 0.9.x/ │ │ ├── OpenSCENARIO_Catalog.xsd │ │ ├── OpenSCENARIO_TypeDefs.xsd │ │ ├── OpenSCENARIO_v0.9.1.xsd │ │ └── migration0_9_1to1_0.xslt │ └── OpenSCENARIO.xsd ├── scenarioconfigs/ │ ├── __init__.py │ ├── openscenario_configuration.py │ ├── route_scenario_configuration.py │ └── scenario_configuration.py ├── scenariomanager/ │ ├── __init__.py │ ├── actorcontrols/ │ │ ├── __init__.py │ │ ├── actor_control.py │ │ ├── basic_control.py │ │ ├── external_control.py │ │ ├── npc_vehicle_control.py │ │ ├── pedestrian_control.py │ │ ├── simple_vehicle_control.py │ │ └── vehicle_longitudinal_control.py │ ├── carla_data_provider.py │ ├── result_writer.py │ ├── scenario_manager.py │ ├── scenarioatomics/ │ │ ├── __init__.py │ │ ├── atomic_behaviors.py │ │ ├── atomic_criteria.py │ │ └── atomic_trigger_conditions.py │ ├── timer.py │ ├── traffic_events.py │ ├── watchdog.py │ └── weather_sim.py ├── scenarios/ │ ├── __init__.py │ ├── background_activity.py │ ├── basic_scenario.py │ ├── change_lane.py │ ├── control_loss.py │ ├── cut_in.py │ ├── follow_leading_vehicle.py │ ├── freeride.py │ ├── junction_crossing_route.py │ ├── maneuver_opposite_direction.py │ ├── master_scenario.py │ ├── no_signal_junction_crossing.py │ ├── object_crash_intersection.py │ ├── object_crash_vehicle.py │ ├── open_scenario.py │ ├── opposite_vehicle_taking_priority.py │ ├── other_leading_vehicle.py │ ├── route_scenario.py │ ├── signalized_junction_left_turn.py │ └── signalized_junction_right_turn.py ├── tools/ │ ├── __init__.py │ ├── openscenario_parser.py │ ├── py_trees_port.py │ ├── route_manipulation.py │ ├── route_parser.py │ ├── scenario_helper.py │ └── scenario_parser.py └── utilities/ └── code_check_and_formatting.sh ================================================ FILE CONTENTS ================================================ ================================================ FILE: .github/FUNDING.yml ================================================ # These are supported funding model platforms github: [OpenDriveLab] # Replace with up to 4 GitHub Sponsors-enabled usernames e.g., [user1, user2] patreon: # Replace with a single Patreon username open_collective: # Replace with a single Open Collective username ko_fi: # Replace with a single Ko-fi username tidelift: # Replace with a single Tidelift platform-name/package-name e.g., npm/babel community_bridge: # Replace with a single Community Bridge project-name e.g., cloud-foundry liberapay: # Replace with a single Liberapay username issuehunt: # Replace with a single IssueHunt username otechie: # Replace with a single Otechie username lfx_crowdfunding: # Replace with a single LFX Crowdfunding project-name e.g., cloud-foundry custom: # Replace with up to 4 custom sponsorship URLs e.g., ['link1', 'link2'] ================================================ FILE: .gitignore ================================================ *.log *results.json *results*.json *.pyc *.out nohup.out *.out events* *hparams.yaml ckpt/ *checkpoints* __pycache__ *work_dirs* *batchscript* build *egg-info* *cpython* collect_data_json/*.json dataset/town??_?? *dataset_metadata.pkl* closed_loop_eval_log/eval_log/* *old_version* ================================================ FILE: LICENSE ================================================ Apache License Version 2.0, January 2004 http://www.apache.org/licenses/ TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION 1. Definitions. "License" shall mean the terms and conditions for use, reproduction, and distribution as defined by Sections 1 through 9 of this document. "Licensor" shall mean the copyright owner or entity authorized by the copyright owner that is granting the License. "Legal Entity" shall mean the union of the acting entity and all other entities that control, are controlled by, or are under common control with that entity. For the purposes of this definition, "control" means (i) the power, direct or indirect, to cause the direction or management of such entity, whether by contract or otherwise, or (ii) ownership of fifty percent (50%) or more of the outstanding shares, or (iii) beneficial ownership of such entity. "You" (or "Your") shall mean an individual or Legal Entity exercising permissions granted by this License. "Source" form shall mean the preferred form for making modifications, including but not limited to software source code, documentation source, and configuration files. "Object" form shall mean any form resulting from mechanical transformation or translation of a Source form, including but not limited to compiled object code, generated documentation, and conversions to other media types. "Work" shall mean the work of authorship, whether in Source or Object form, made available under the License, as indicated by a copyright notice that is included in or attached to the work (an example is provided in the Appendix below). "Derivative Works" shall mean any work, whether in Source or Object form, that is based on (or derived from) the Work and for which the editorial revisions, annotations, elaborations, or other modifications represent, as a whole, an original work of authorship. For the purposes of this License, Derivative Works shall not include works that remain separable from, or merely link (or bind by name) to the interfaces of, the Work and Derivative Works thereof. "Contribution" shall mean any work of authorship, including the original version of the Work and any modifications or additions to that Work or Derivative Works thereof, that is intentionally submitted to Licensor for inclusion in the Work by the copyright owner or by an individual or Legal Entity authorized to submit on behalf of the copyright owner. For the purposes of this definition, "submitted" means any form of electronic, verbal, or written communication sent to the Licensor or its representatives, including but not limited to communication on electronic mailing lists, source code control systems, and issue tracking systems that are managed by, or on behalf of, the Licensor for the purpose of discussing and improving the Work, but excluding communication that is conspicuously marked or otherwise designated in writing by the copyright owner as "Not a Contribution." "Contributor" shall mean Licensor and any individual or Legal Entity on behalf of whom a Contribution has been received by Licensor and subsequently incorporated within the Work. 2. Grant of Copyright License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable copyright license to reproduce, prepare Derivative Works of, publicly display, publicly perform, sublicense, and distribute the Work and such Derivative Works in Source or Object form. 3. Grant of Patent License. Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable (except as stated in this section) patent license to make, have made, use, offer to sell, sell, import, and otherwise transfer the Work, where such license applies only to those patent claims licensable by such Contributor that are necessarily infringed by their Contribution(s) alone or by combination of their Contribution(s) with the Work to which such Contribution(s) was submitted. If You institute patent litigation against any entity (including a cross-claim or counterclaim in a lawsuit) alleging that the Work or a Contribution incorporated within the Work constitutes direct or contributory patent infringement, then any patent licenses granted to You under this License for that Work shall terminate as of the date such litigation is filed. 4. Redistribution. You may reproduce and distribute copies of the Work or Derivative Works thereof in any medium, with or without modifications, and in Source or Object form, provided that You meet the following conditions: (a) You must give any other recipients of the Work or Derivative Works a copy of this License; and (b) You must cause any modified files to carry prominent notices stating that You changed the files; and (c) You must retain, in the Source form of any Derivative Works that You distribute, all copyright, patent, trademark, and attribution notices from the Source form of the Work, excluding those notices that do not pertain to any part of the Derivative Works; and (d) If the Work includes a "NOTICE" text file as part of its distribution, then any Derivative Works that You distribute must include a readable copy of the attribution notices contained within such NOTICE file, excluding those notices that do not pertain to any part of the Derivative Works, in at least one of the following places: within a NOTICE text file distributed as part of the Derivative Works; within the Source form or documentation, if provided along with the Derivative Works; or, within a display generated by the Derivative Works, if and wherever such third-party notices normally appear. The contents of the NOTICE file are for informational purposes only and do not modify the License. You may add Your own attribution notices within Derivative Works that You distribute, alongside or as an addendum to the NOTICE text from the Work, provided that such additional attribution notices cannot be construed as modifying the License. You may add Your own copyright statement to Your modifications and may provide additional or different license terms and conditions for use, reproduction, or distribution of Your modifications, or for any such Derivative Works as a whole, provided Your use, reproduction, and distribution of the Work otherwise complies with the conditions stated in this License. 5. Submission of Contributions. Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions. 6. Trademarks. This License does not grant permission to use the trade names, trademarks, service marks, or product names of the Licensor, except as required for reasonable and customary use in describing the origin of the Work and reproducing the content of the NOTICE file. 7. Disclaimer of Warranty. Unless required by applicable law or agreed to in writing, Licensor provides the Work (and each Contributor provides its Contributions) on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied, including, without limitation, any warranties or conditions of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A PARTICULAR PURPOSE. You are solely responsible for determining the appropriateness of using or redistributing the Work and assume any risks associated with Your exercise of permissions under this License. 8. Limitation of Liability. In no event and under no legal theory, whether in tort (including negligence), contract, or otherwise, unless required by applicable law (such as deliberate and grossly negligent acts) or agreed to in writing, shall any Contributor be liable to You for damages, including any direct, indirect, special, incidental, or consequential damages of any character arising as a result of this License or out of the use or inability to use the Work (including but not limited to damages for loss of goodwill, work stoppage, computer failure or malfunction, or any and all other commercial damages or losses), even if such Contributor has been advised of the possibility of such damages. 9. Accepting Warranty or Additional Liability. While redistributing the Work or Derivative Works thereof, You may choose to offer, and charge a fee for, acceptance of support, warranty, indemnity, or other liability obligations and/or rights consistent with this License. However, in accepting such obligations, You may act only on Your own behalf and on Your sole responsibility, not on behalf of any other Contributor, and only if You agree to indemnify, defend, and hold each Contributor harmless for any liability incurred by, or claims asserted against, such Contributor by reason of your accepting any such warranty or additional liability. END OF TERMS AND CONDITIONS APPENDIX: How to apply the Apache License to your work. To apply the Apache License to your work, attach the following boilerplate notice, with the fields enclosed by brackets "[]" replaced with your own identifying information. (Don't include the brackets!) The text should be enclosed in the appropriate comment syntax for the file format. We also recommend that a file or class name and description of purpose be included on the same "printed page" as the copyright notice for easier identification within third-party archives. Copyright [yyyy] [name of copyright owner] Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. ================================================ FILE: README.md ================================================ > [!IMPORTANT] > 🌟 Stay up to date at [opendrivelab.com](https://opendrivelab.com/#news)! # Think Twice before Driving: Towards Scalable Decoders for End-to-End Autonomous Driving - A SOTA Decoder for End-to-End Autonomous Driving under BEV - [arXiv Paper](https://arxiv.org/abs/2305.06242) (CVPR 2023) ![pipeline](src/pipeline.PNG) ## Demo Video [![Demo](src/demo_start.png)](https://youtu.be/ZhSH63O4Hsg) ## Getting Started - [Installation](docs/INSTALL.md) - [Closed-Loop Evaluation in Carla](docs/EVAL.md) - [Prepare Dataset](docs/DATA_PREP.md) - [Train Your Own Model](docs/TRAIN.md) - [Calibrations for Different Camera Settings](camera_calibration/README.md) (Optional) ## Quick Run in Carla Install the environment as in [Installation](docs/INSTALL.md), download our checkpoint ([GoogleDrive](https://drive.google.com/file/d/1Y2bWf8qVwqVQxqM2GOKTiR9kE9nGtkYV/view?usp=share_link) or [BaiduYun](https://pan.baidu.com/s/1OamwKOUpqK0EOqWa1Luv_g)(提取码 m5di).) (189K frames training set), put it into **open_loop_training/ckpt**, and run: ```shell ## In the ThinkTwice/ directory CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/evaluation_town05long.sh 22023 22033 thinktwice_agent False True open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py all_towns_traffic_scenarios_no256 thinktwice_town05long 2>&1 > thinktwice_town05long.log & ``` Check [closed_loop_eval_log/eval_log](closed_loop_eval_log/eval_log) to see how our model drives in Carla! :oncoming_automobile: (In case you have a screen to see the interface of Carla simulator, you could remove *DISPLAY=* in [leaderboard/leaderboard/leaderboard_evaluator.py](leaderboard/leaderboard/leaderboard_evaluator.py) and then you could directly watch with Carla.) ## Code Structure We give the structure of our code. Note that we only introduce those folders/files are commonly used and modified. ThinkTwice/ ├── agents # From Carla official ├── camera_calibration # When you want to use cameras with different FOV ├── closed_loop_eval_log # Save eval logs ├── collect_data_json # Save data collection logs ├── dataset # Data and metadata for training ├── leaderboard # Code for Closed-Loop Evaluation │ ├── data # Save routes and scenarios │ ├── scripts # Run with Carla │ ├── team_code # Your | | ├── roach_ap_agent_data_collection.py # Data collection │ | └── thinktwice_agent.py # Interface for closed-loop evaluation of our model │ ├── leaderboard # From Carla official | | └── leaderboard_evaluator.py # Entrance of closed-loop evaluation ├── roach # Roach for data collection ├── scenario_runner # From Carla official ├── open_loop_training # Training and Neural Network | ├── ckpt # Checkpoints | ├── work_dirs # Training Log | ├── code # Preprocessing, DataLoader, Model | │ ├── apis # Training pipeline for mmdet3D | │ ├── core # The hooks for mmdet3D | │ ├── datasets # Preprocessing and DataLoader | | | ├── pipelines # Functions of Preprocessing and DataLoader | │ | ├── samplers # For DDP | │ | └── carla_dataset.py # Framework of Preprocessing and DataLoading | │ ├── model_code # Neural Network | | | ├── backbones # Module of Encoder | | | └── dense_heads # Module of Decoder and Loss Functions | │ └── encoder_decoder_framework.py # Entrance of Neural Network | └── train.py # Entrance of Training ## License All assets and code are under the [Apache 2.0 license](./LICENSE) unless specified otherwise. ## Bibtex If this work is helpful for your research, please consider citing the following BibTeX entry. ``` @inproceedings{jia2023thinktwice, title={Think Twice before Driving: Towards Scalable Decoders for End-to-End Autonomous Driving}, author={Jia, Xiaosong and Wu, Penghao and Chen, Li and Xie, Jiangwei and He, Conghui and Yan, Junchi and Li, Hongyang}, booktitle={CVPR}, year={2023} } ``` ## Related Resources Many thanks to the open-source community! [![Awesome](https://awesome.re/badge.svg)](https://awesome.re) - [End-to-end Autonomous Driving Survey](https://github.com/OpenDriveLab/End-to-end-Autonomous-Driving) (:rocket:Ours!) - [TCP](https://github.com/OpenPerceptionX/TCP) (:rocket:Ours!) - [BEVFormer](https://github.com/fundamentalvision/BEVFormer) (:rocket:Ours!) - [UniAD](https://github.com/OpenDriveLab/UniAD) (:rocket:Ours!) - [ST-P3](https://github.com/OpenPerceptionX/ST-P3) (:rocket:Ours!) - [Carla](https://github.com/carla-simulator/carla) - [Roach](https://github.com/zhejz/carla-roach) - [Transfuser](https://github.com/autonomousvision/transfuser) - [CARLA_GARGE](https://github.com/autonomousvision/carla_garage) - [LAV](https://github.com/dotchen/LAV) - [IBISCape](https://github.com/AbanobSoliman/IBISCape) ================================================ FILE: agents/__init__.py ================================================ ================================================ FILE: agents/navigation/__init__.py ================================================ ================================================ FILE: agents/navigation/agent.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module implements an agent that roams around a track following random waypoints and avoiding other vehicles. The agent also responds to traffic lights. """ import sys import math from enum import Enum import carla from agents.tools.misc import is_within_distance_ahead, is_within_distance, compute_distance class AgentState(Enum): """ AGENT_STATE represents the possible states of a roaming agent """ NAVIGATING = 1 BLOCKED_BY_VEHICLE = 2 BLOCKED_RED_LIGHT = 3 class Agent(object): """Base class to define agents in CARLA""" def __init__(self, vehicle): """ Constructor method. :param vehicle: actor to apply to local planner logic onto """ self._vehicle = vehicle self._proximity_tlight_threshold = 5.0 # meters self._proximity_vehicle_threshold = 10.0 # meters self._local_planner = None self._world = self._vehicle.get_world() try: self._map = self._world.get_map() except RuntimeError as error: print('RuntimeError: {}'.format(error)) print(' The server could not send the OpenDRIVE (.xodr) file:') print(' Make sure it exists, has the same name of your town, and is correct.') sys.exit(1) self._last_traffic_light = None def get_local_planner(self): """Get method for protected member local planner""" return self._local_planner @staticmethod def run_step(debug=False): """ Execute one step of navigation. :param debug: boolean flag for debugging :return: control """ control = carla.VehicleControl() if debug: control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False control.manual_gear_shift = False return control def _is_light_red(self, lights_list): """ Method to check if there is a red light affecting us. This version of the method is compatible with both European and US style traffic lights. :param lights_list: list containing TrafficLight objects :return: a tuple given by (bool_flag, traffic_light), where - bool_flag is True if there is a traffic light in RED affecting us and False otherwise - traffic_light is the object itself or None if there is no red traffic light affecting us """ ego_vehicle_location = self._vehicle.get_location() ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location) for traffic_light in lights_list: object_location = self._get_trafficlight_trigger_location(traffic_light) object_waypoint = self._map.get_waypoint(object_location) if object_waypoint.road_id != ego_vehicle_waypoint.road_id: continue ve_dir = ego_vehicle_waypoint.transform.get_forward_vector() wp_dir = object_waypoint.transform.get_forward_vector() dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z if dot_ve_wp < 0: continue if is_within_distance_ahead(object_waypoint.transform, self._vehicle.get_transform(), self._proximity_tlight_threshold): if traffic_light.state == carla.TrafficLightState.Red: return (True, traffic_light) return (False, None) def _get_trafficlight_trigger_location(self, traffic_light): # pylint: disable=no-self-use """ Calculates the yaw of the waypoint that represents the trigger volume of the traffic light """ def rotate_point(point, radians): """ rotate a given point by a given angle """ rotated_x = math.cos(radians) * point.x - math.sin(radians) * point.y rotated_y = math.sin(radians) * point.x - math.cos(radians) * point.y return carla.Vector3D(rotated_x, rotated_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), math.radians(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) def _bh_is_vehicle_hazard(self, ego_wpt, ego_loc, vehicle_list, proximity_th, up_angle_th, low_angle_th=0, lane_offset=0): """ Check if a given vehicle is an obstacle in our way. To this end we take into account the road and lane the target vehicle is on and run a geometry test to check if the target vehicle is under a certain distance in front of our ego vehicle. We also check the next waypoint, just to be sure there's not a sudden road id change. WARNING: This method is an approximation that could fail for very large vehicles, which center is actually on a different lane but their extension falls within the ego vehicle lane. Also, make sure to remove the ego vehicle from the list. Lane offset is set to +1 for right lanes and -1 for left lanes, but this has to be inverted if lane values are negative. :param ego_wpt: waypoint of ego-vehicle :param ego_log: location of ego-vehicle :param vehicle_list: list of potential obstacle to check :param proximity_th: threshold for the agent to be alerted of a possible collision :param up_angle_th: upper threshold for angle :param low_angle_th: lower threshold for angle :param lane_offset: for right and left lane changes :return: a tuple given by (bool_flag, vehicle, distance), where: - bool_flag is True if there is a vehicle ahead blocking us and False otherwise - vehicle is the blocker object itself - distance is the meters separating the two vehicles """ # Get the right offset if ego_wpt.lane_id < 0 and lane_offset != 0: lane_offset *= -1 for target_vehicle in vehicle_list: target_vehicle_loc = target_vehicle.get_location() # If the object is not in our next or current lane it's not an obstacle target_wpt = self._map.get_waypoint(target_vehicle_loc) if target_wpt.road_id != ego_wpt.road_id or \ target_wpt.lane_id != ego_wpt.lane_id + lane_offset: next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=5)[0] if target_wpt.road_id != next_wpt.road_id or \ target_wpt.lane_id != next_wpt.lane_id + lane_offset: continue if is_within_distance(target_vehicle_loc, ego_loc, self._vehicle.get_transform().rotation.yaw, proximity_th, up_angle_th, low_angle_th): return (True, target_vehicle, compute_distance(target_vehicle_loc, ego_loc)) return (False, None, -1) def _is_vehicle_hazard(self, vehicle_list): """ :param vehicle_list: list of potential obstacle to check :return: a tuple given by (bool_flag, vehicle), where - bool_flag is True if there is a vehicle ahead blocking us and False otherwise - vehicle is the blocker object itself """ ego_vehicle_location = self._vehicle.get_location() ego_vehicle_waypoint = self._map.get_waypoint(ego_vehicle_location) for target_vehicle in vehicle_list: # do not account for the ego vehicle if target_vehicle.id == self._vehicle.id: continue # if the object is not in our lane it's not an obstacle target_vehicle_waypoint = self._map.get_waypoint(target_vehicle.get_location()) if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \ target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id: continue if is_within_distance_ahead(target_vehicle.get_transform(), self._vehicle.get_transform(), self._proximity_vehicle_threshold): return (True, target_vehicle) return (False, None) @staticmethod def emergency_stop(): """ Send an emergency stop command to the vehicle :return: control for braking """ control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 1.0 control.hand_brake = False return control ================================================ FILE: agents/navigation/basic_agent.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module implements an agent that roams around a track following random waypoints and avoiding other vehicles. The agent also responds to traffic lights. """ import carla from agents.navigation.agent import Agent, AgentState from agents.navigation.local_planner import LocalPlanner from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO class BasicAgent(Agent): """ BasicAgent implements a basic agent that navigates scenes to reach a given target destination. This agent respects traffic lights and other vehicles. """ def __init__(self, vehicle, target_speed=20): """ :param vehicle: actor to apply to local planner logic onto """ super(BasicAgent, self).__init__(vehicle) self._proximity_tlight_threshold = 5.0 # meters self._proximity_vehicle_threshold = 10.0 # meters self._state = AgentState.NAVIGATING args_lateral_dict = { 'K_P': 1, 'K_D': 0.4, 'K_I': 0, 'dt': 1.0/20.0} self._local_planner = LocalPlanner( self._vehicle, opt_dict={'target_speed' : target_speed, 'lateral_control_dict':args_lateral_dict}) self._hop_resolution = 2.0 self._path_seperation_hop = 2 self._path_seperation_threshold = 0.5 self._target_speed = target_speed self._grp = None def set_destination(self, location): """ This method creates a list of waypoints from agent's position to destination location based on the route returned by the global router """ start_waypoint = self._map.get_waypoint(self._vehicle.get_location()) end_waypoint = self._map.get_waypoint( carla.Location(location[0], location[1], location[2])) route_trace = self._trace_route(start_waypoint, end_waypoint) self._local_planner.set_global_plan(route_trace) def _trace_route(self, start_waypoint, end_waypoint): """ This method sets up a global router and returns the optimal route from start_waypoint to end_waypoint """ # Setting up global router if self._grp is None: dao = GlobalRoutePlannerDAO(self._vehicle.get_world().get_map(), self._hop_resolution) grp = GlobalRoutePlanner(dao) grp.setup() self._grp = grp # Obtain route plan route = self._grp.trace_route( start_waypoint.transform.location, end_waypoint.transform.location) return route def run_step(self, debug=False): """ Execute one step of navigation. :return: carla.VehicleControl """ # is there an obstacle in front of us? hazard_detected = False # retrieve relevant elements for safe navigation, i.e.: traffic lights # and other vehicles actor_list = self._world.get_actors() vehicle_list = actor_list.filter("*vehicle*") lights_list = actor_list.filter("*traffic_light*") # check possible obstacles vehicle_state, vehicle = self._is_vehicle_hazard(vehicle_list) if vehicle_state: if debug: print('!!! VEHICLE BLOCKING AHEAD [{}])'.format(vehicle.id)) self._state = AgentState.BLOCKED_BY_VEHICLE hazard_detected = True # check for the state of the traffic lights light_state, traffic_light = self._is_light_red(lights_list) if light_state: if debug: print('=== RED LIGHT AHEAD [{}])'.format(traffic_light.id)) self._state = AgentState.BLOCKED_RED_LIGHT hazard_detected = True if hazard_detected: control = self.emergency_stop() else: self._state = AgentState.NAVIGATING # standard local planner behavior control = self._local_planner.run_step(debug=debug) return control def done(self): """ Check whether the agent has reached its destination. :return bool """ return self._local_planner.done() ================================================ FILE: agents/navigation/behavior_agent.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module implements an agent that roams around a track following random waypoints and avoiding other vehicles. The agent also responds to traffic lights, traffic signs, and has different possible configurations. """ import random import numpy as np import carla from agents.navigation.agent import Agent from agents.navigation.local_planner_behavior import LocalPlanner, RoadOption from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO from agents.navigation.types_behavior import Cautious, Aggressive, Normal from agents.tools.misc import get_speed, positive class BehaviorAgent(Agent): """ BehaviorAgent implements an agent that navigates scenes to reach a given target destination, by computing the shortest possible path to it. This agent can correctly follow traffic signs, speed limitations, traffic lights, while also taking into account nearby vehicles. Lane changing decisions can be taken by analyzing the surrounding environment, such as overtaking or tailgating avoidance. Adding to these are possible behaviors, the agent can also keep safety distance from a car in front of it by tracking the instantaneous time to collision and keeping it in a certain range. Finally, different sets of behaviors are encoded in the agent, from cautious to a more aggressive ones. """ def __init__(self, vehicle, ignore_traffic_light=False, behavior='normal'): """ Constructor method. :param vehicle: actor to apply to local planner logic onto :param ignore_traffic_light: boolean to ignore any traffic light :param behavior: type of agent to apply """ super(BehaviorAgent, self).__init__(vehicle) self.vehicle = vehicle self.ignore_traffic_light = ignore_traffic_light self._local_planner = LocalPlanner(self) self._grp = None self.look_ahead_steps = 0 # Vehicle information self.speed = 0 self.speed_limit = 0 self.direction = None self.incoming_direction = None self.incoming_waypoint = None self.start_waypoint = None self.end_waypoint = None self.is_at_traffic_light = 0 self.light_state = "Green" self.light_id_to_ignore = -1 self.min_speed = 5 self.behavior = None self._sampling_resolution = 4.5 # Parameters for agent behavior if behavior == 'cautious': self.behavior = Cautious() elif behavior == 'normal': self.behavior = Normal() elif behavior == 'aggressive': self.behavior = Aggressive() def update_information(self, world): """ This method updates the information regarding the ego vehicle based on the surrounding world. :param world: carla.world object """ self.speed = get_speed(self.vehicle) self.speed_limit = world.player.get_speed_limit() self._local_planner.set_speed(self.speed_limit) self.direction = self._local_planner.target_road_option if self.direction is None: self.direction = RoadOption.LANEFOLLOW self.look_ahead_steps = int((self.speed_limit) / 10) self.incoming_waypoint, self.incoming_direction = self._local_planner.get_incoming_waypoint_and_direction( steps=self.look_ahead_steps) if self.incoming_direction is None: self.incoming_direction = RoadOption.LANEFOLLOW self.is_at_traffic_light = world.player.is_at_traffic_light() if self.ignore_traffic_light: self.light_state = "Green" else: # This method also includes stop signs and intersections. self.light_state = str(self.vehicle.get_traffic_light_state()) def set_destination(self, start_location, end_location, clean=False): """ This method creates a list of waypoints from agent's position to destination location based on the route returned by the global router. :param start_location: initial position :param end_location: final position :param clean: boolean to clean the waypoint queue """ if clean: self._local_planner.waypoints_queue.clear() self.start_waypoint = self._map.get_waypoint(start_location) self.end_waypoint = self._map.get_waypoint(end_location) route_trace = self._trace_route(self.start_waypoint, self.end_waypoint) self._local_planner.set_global_plan(route_trace, clean) def reroute(self, spawn_points): """ This method implements re-routing for vehicles approaching its destination. It finds a new target and computes another path to reach it. :param spawn_points: list of possible destinations for the agent """ print("Target almost reached, setting new destination...") random.shuffle(spawn_points) new_start = self._local_planner.waypoints_queue[-1][0].transform.location destination = spawn_points[0].location if spawn_points[0].location != new_start else spawn_points[1].location print("New destination: " + str(destination)) self.set_destination(new_start, destination) def _trace_route(self, start_waypoint, end_waypoint): """ This method sets up a global router and returns the optimal route from start_waypoint to end_waypoint. :param start_waypoint: initial position :param end_waypoint: final position """ # Setting up global router if self._grp is None: wld = self.vehicle.get_world() dao = GlobalRoutePlannerDAO( wld.get_map(), sampling_resolution=self._sampling_resolution) grp = GlobalRoutePlanner(dao) grp.setup() self._grp = grp # Obtain route plan route = self._grp.trace_route( start_waypoint.transform.location, end_waypoint.transform.location) return route def traffic_light_manager(self, waypoint): """ This method is in charge of behaviors for red lights and stops. WARNING: What follows is a proxy to avoid having a car brake after running a yellow light. This happens because the car is still under the influence of the semaphore, even after passing it. So, the semaphore id is temporarely saved to ignore it and go around this issue, until the car is near a new one. :param waypoint: current waypoint of the agent """ light_id = self.vehicle.get_traffic_light().id if self.vehicle.get_traffic_light() is not None else -1 if self.light_state == "Red": if not waypoint.is_junction and (self.light_id_to_ignore != light_id or light_id == -1): return 1 elif waypoint.is_junction and light_id != -1: self.light_id_to_ignore = light_id if self.light_id_to_ignore != light_id: self.light_id_to_ignore = -1 return 0 def _overtake(self, location, waypoint, vehicle_list): """ This method is in charge of overtaking behaviors. :param location: current location of the agent :param waypoint: current waypoint of the agent :param vehicle_list: list of all the nearby vehicles """ left_turn = waypoint.left_lane_marking.lane_change right_turn = waypoint.right_lane_marking.lane_change left_wpt = waypoint.get_left_lane() right_wpt = waypoint.get_right_lane() if (left_turn == carla.LaneChange.Left or left_turn == carla.LaneChange.Both) and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving: new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=180, lane_offset=-1) if not new_vehicle_state: print("Overtaking to the left!") self.behavior.overtake_counter = 200 self.set_destination(left_wpt.transform.location, self.end_waypoint.transform.location, clean=True) elif right_turn == carla.LaneChange.Right and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving: new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=180, lane_offset=1) if not new_vehicle_state: print("Overtaking to the right!") self.behavior.overtake_counter = 200 self.set_destination(right_wpt.transform.location, self.end_waypoint.transform.location, clean=True) def _tailgating(self, location, waypoint, vehicle_list): """ This method is in charge of tailgating behaviors. :param location: current location of the agent :param waypoint: current waypoint of the agent :param vehicle_list: list of all the nearby vehicles """ left_turn = waypoint.left_lane_marking.lane_change right_turn = waypoint.right_lane_marking.lane_change left_wpt = waypoint.get_left_lane() right_wpt = waypoint.get_right_lane() behind_vehicle_state, behind_vehicle, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, low_angle_th=160) if behind_vehicle_state and self.speed < get_speed(behind_vehicle): if (right_turn == carla.LaneChange.Right or right_turn == carla.LaneChange.Both) and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving: new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=1) if not new_vehicle_state: print("Tailgating, moving to the right!") self.behavior.tailgate_counter = 200 self.set_destination(right_wpt.transform.location, self.end_waypoint.transform.location, clean=True) elif left_turn == carla.LaneChange.Left and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving: new_vehicle_state, _, _ = self._bh_is_vehicle_hazard(waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=-1) if not new_vehicle_state: print("Tailgating, moving to the left!") self.behavior.tailgate_counter = 200 self.set_destination(left_wpt.transform.location, self.end_waypoint.transform.location, clean=True) def collision_and_car_avoid_manager(self, location, waypoint): """ This module is in charge of warning in case of a collision and managing possible overtaking or tailgating chances. :param location: current location of the agent :param waypoint: current waypoint of the agent :return vehicle_state: True if there is a vehicle nearby, False if not :return vehicle: nearby vehicle :return distance: distance to nearby vehicle """ vehicle_list = self._world.get_actors().filter("*vehicle*") def dist(v): return v.get_location().distance(waypoint.transform.location) vehicle_list = [v for v in vehicle_list if dist(v) < 45 and v.id != self.vehicle.id] if self.direction == RoadOption.CHANGELANELEFT: vehicle_state, vehicle, distance = self._bh_is_vehicle_hazard( waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=-1) elif self.direction == RoadOption.CHANGELANERIGHT: vehicle_state, vehicle, distance = self._bh_is_vehicle_hazard( waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=180, lane_offset=1) else: vehicle_state, vehicle, distance = self._bh_is_vehicle_hazard( waypoint, location, vehicle_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=30) # Check for overtaking if vehicle_state and self.direction == RoadOption.LANEFOLLOW and \ not waypoint.is_junction and self.speed > 10 \ and self.behavior.overtake_counter == 0 and self.speed > get_speed(vehicle): self._overtake(location, waypoint, vehicle_list) # Check for tailgating elif not vehicle_state and self.direction == RoadOption.LANEFOLLOW \ and not waypoint.is_junction and self.speed > 10 \ and self.behavior.tailgate_counter == 0: self._tailgating(location, waypoint, vehicle_list) return vehicle_state, vehicle, distance def pedestrian_avoid_manager(self, location, waypoint): """ This module is in charge of warning in case of a collision with any pedestrian. :param location: current location of the agent :param waypoint: current waypoint of the agent :return vehicle_state: True if there is a walker nearby, False if not :return vehicle: nearby walker :return distance: distance to nearby walker """ walker_list = self._world.get_actors().filter("*walker.pedestrian*") def dist(w): return w.get_location().distance(waypoint.transform.location) walker_list = [w for w in walker_list if dist(w) < 10] if self.direction == RoadOption.CHANGELANELEFT: walker_state, walker, distance = self._bh_is_vehicle_hazard(waypoint, location, walker_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=90, lane_offset=-1) elif self.direction == RoadOption.CHANGELANERIGHT: walker_state, walker, distance = self._bh_is_vehicle_hazard(waypoint, location, walker_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 2), up_angle_th=90, lane_offset=1) else: walker_state, walker, distance = self._bh_is_vehicle_hazard(waypoint, location, walker_list, max( self.behavior.min_proximity_threshold, self.speed_limit / 3), up_angle_th=60) return walker_state, walker, distance def car_following_manager(self, vehicle, distance, debug=False): """ Module in charge of car-following behaviors when there's someone in front of us. :param vehicle: car to follow :param distance: distance from vehicle :param debug: boolean for debugging :return control: carla.VehicleControl """ vehicle_speed = get_speed(vehicle) delta_v = max(1, (self.speed - vehicle_speed) / 3.6) ttc = distance / delta_v if delta_v != 0 else distance / np.nextafter(0., 1.) # Under safety time distance, slow down. if self.behavior.safety_time > ttc > 0.0: control = self._local_planner.run_step( target_speed=min(positive(vehicle_speed - self.behavior.speed_decrease), min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist)), debug=debug) # Actual safety distance area, try to follow the speed of the vehicle in front. elif 2 * self.behavior.safety_time > ttc >= self.behavior.safety_time: control = self._local_planner.run_step( target_speed=min(max(self.min_speed, vehicle_speed), min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist)), debug=debug) # Normal behavior. else: control = self._local_planner.run_step( target_speed= min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist), debug=debug) return control def run_step(self, debug=False): """ Execute one step of navigation. :param debug: boolean for debugging :return control: carla.VehicleControl """ control = None if self.behavior.tailgate_counter > 0: self.behavior.tailgate_counter -= 1 if self.behavior.overtake_counter > 0: self.behavior.overtake_counter -= 1 ego_vehicle_loc = self.vehicle.get_location() ego_vehicle_wp = self._map.get_waypoint(ego_vehicle_loc) # 1: Red lights and stops behavior if self.traffic_light_manager(ego_vehicle_wp) != 0: return self.emergency_stop() # 2.1: Pedestrian avoidancd behaviors walker_state, walker, w_distance = self.pedestrian_avoid_manager( ego_vehicle_loc, ego_vehicle_wp) if walker_state: # Distance is computed from the center of the two cars, # we use bounding boxes to calculate the actual distance distance = w_distance - max( walker.bounding_box.extent.y, walker.bounding_box.extent.x) - max( self.vehicle.bounding_box.extent.y, self.vehicle.bounding_box.extent.x) # Emergency brake if the car is very close. if distance < self.behavior.braking_distance: return self.emergency_stop() # 2.2: Car following behaviors vehicle_state, vehicle, distance = self.collision_and_car_avoid_manager( ego_vehicle_loc, ego_vehicle_wp) if vehicle_state: # Distance is computed from the center of the two cars, # we use bounding boxes to calculate the actual distance distance = distance - max( vehicle.bounding_box.extent.y, vehicle.bounding_box.extent.x) - max( self.vehicle.bounding_box.extent.y, self.vehicle.bounding_box.extent.x) # Emergency brake if the car is very close. if distance < self.behavior.braking_distance: return self.emergency_stop() else: control = self.car_following_manager(vehicle, distance) # 4: Intersection behavior # Checking if there's a junction nearby to slow down elif self.incoming_waypoint.is_junction and (self.incoming_direction == RoadOption.LEFT or self.incoming_direction == RoadOption.RIGHT): control = self._local_planner.run_step( target_speed=min(self.behavior.max_speed, self.speed_limit - 5), debug=debug) # 5: Normal behavior # Calculate controller based on no turn, traffic light or vehicle in front else: control = self._local_planner.run_step( target_speed= min(self.behavior.max_speed, self.speed_limit - self.behavior.speed_lim_dist), debug=debug) return control ================================================ FILE: agents/navigation/controller.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains PID controllers to perform lateral and longitudinal control. """ from collections import deque import math import numpy as np import carla from agents.tools.misc import get_speed class VehiclePIDController(): """ VehiclePIDController is the combination of two PID controllers (lateral and longitudinal) to perform the low level control a vehicle from client side """ def __init__(self, vehicle, args_lateral, args_longitudinal, max_throttle=0.75, max_brake=0.3, max_steering=0.8): """ Constructor method. :param vehicle: actor to apply to local planner logic onto :param args_lateral: dictionary of arguments to set the lateral PID controller using the following semantics: K_P -- Proportional term K_D -- Differential term K_I -- Integral term :param args_longitudinal: dictionary of arguments to set the longitudinal PID controller using the following semantics: K_P -- Proportional term K_D -- Differential term K_I -- Integral term """ self.max_brake = max_brake self.max_throt = max_throttle self.max_steer = max_steering self._vehicle = vehicle self._world = self._vehicle.get_world() self.past_steering = self._vehicle.get_control().steer self._lon_controller = PIDLongitudinalController(self._vehicle, **args_longitudinal) self._lat_controller = PIDLateralController(self._vehicle, **args_lateral) def run_step(self, target_speed, waypoint): """ Execute one step of control invoking both lateral and longitudinal PID controllers to reach a target waypoint at a given target_speed. :param target_speed: desired vehicle speed :param waypoint: target location encoded as a waypoint :return: distance (in meters) to the waypoint """ acceleration = self._lon_controller.run_step(target_speed) current_steering = self._lat_controller.run_step(waypoint) control = carla.VehicleControl() if acceleration >= 0.0: control.throttle = min(acceleration, self.max_throt) control.brake = 0.0 else: control.throttle = 0.0 control.brake = min(abs(acceleration), self.max_brake) # Steering regulation: changes cannot happen abruptly, can't steer too much. if current_steering > self.past_steering + 0.1: current_steering = self.past_steering + 0.1 elif current_steering < self.past_steering - 0.1: current_steering = self.past_steering - 0.1 if current_steering >= 0: steering = min(self.max_steer, current_steering) else: steering = max(-self.max_steer, current_steering) control.steer = steering control.hand_brake = False control.manual_gear_shift = False self.past_steering = steering return control class PIDLongitudinalController(): """ PIDLongitudinalController implements longitudinal control using a PID. """ def __init__(self, vehicle, K_P=1.0, K_D=0.0, K_I=0.0, dt=0.03): """ Constructor method. :param vehicle: actor to apply to local planner logic onto :param K_P: Proportional term :param K_D: Differential term :param K_I: Integral term :param dt: time differential in seconds """ self._vehicle = vehicle self._k_p = K_P self._k_d = K_D self._k_i = K_I self._dt = dt self._error_buffer = deque(maxlen=10) def run_step(self, target_speed, debug=False): """ Execute one step of longitudinal control to reach a given target speed. :param target_speed: target speed in Km/h :param debug: boolean for debugging :return: throttle control """ current_speed = get_speed(self._vehicle) if debug: print('Current speed = {}'.format(current_speed)) return self._pid_control(target_speed, current_speed) def _pid_control(self, target_speed, current_speed): """ Estimate the throttle/brake of the vehicle based on the PID equations :param target_speed: target speed in Km/h :param current_speed: current speed of the vehicle in Km/h :return: throttle/brake control """ error = target_speed - current_speed self._error_buffer.append(error) if len(self._error_buffer) >= 2: _de = (self._error_buffer[-1] - self._error_buffer[-2]) / self._dt _ie = sum(self._error_buffer) * self._dt else: _de = 0.0 _ie = 0.0 return np.clip((self._k_p * error) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0) class PIDLateralController(): """ PIDLateralController implements lateral control using a PID. """ def __init__(self, vehicle, K_P=1.0, K_D=0.0, K_I=0.0, dt=0.03): """ Constructor method. :param vehicle: actor to apply to local planner logic onto :param K_P: Proportional term :param K_D: Differential term :param K_I: Integral term :param dt: time differential in seconds """ self._vehicle = vehicle self._k_p = K_P self._k_d = K_D self._k_i = K_I self._dt = dt self._e_buffer = deque(maxlen=10) def run_step(self, waypoint): """ Execute one step of lateral control to steer the vehicle towards a certain waypoin. :param waypoint: target waypoint :return: steering control in the range [-1, 1] where: -1 maximum steering to left +1 maximum steering to right """ return self._pid_control(waypoint, self._vehicle.get_transform()) def _pid_control(self, waypoint, vehicle_transform): """ Estimate the steering angle of the vehicle based on the PID equations :param waypoint: target waypoint :param vehicle_transform: current transform of the vehicle :return: steering control in the range [-1, 1] """ v_begin = vehicle_transform.location v_end = v_begin + carla.Location(x=math.cos(math.radians(vehicle_transform.rotation.yaw)), y=math.sin(math.radians(vehicle_transform.rotation.yaw))) v_vec = np.array([v_end.x - v_begin.x, v_end.y - v_begin.y, 0.0]) w_vec = np.array([waypoint.transform.location.x - v_begin.x, waypoint.transform.location.y - v_begin.y, 0.0]) _dot = math.acos(np.clip(np.dot(w_vec, v_vec) / (np.linalg.norm(w_vec) * np.linalg.norm(v_vec)), -1.0, 1.0)) _cross = np.cross(v_vec, w_vec) if _cross[2] < 0: _dot *= -1.0 self._e_buffer.append(_dot) if len(self._e_buffer) >= 2: _de = (self._e_buffer[-1] - self._e_buffer[-2]) / self._dt _ie = sum(self._e_buffer) * self._dt else: _de = 0.0 _ie = 0.0 return np.clip((self._k_p * _dot) + (self._k_d * _de) + (self._k_i * _ie), -1.0, 1.0) ================================================ FILE: agents/navigation/global_route_planner.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides GlobalRoutePlanner implementation. """ import math import numpy as np import networkx as nx import carla from agents.navigation.local_planner import RoadOption from agents.tools.misc import vector class GlobalRoutePlanner(object): """ This class provides a very high level route plan. Instantiate the class by passing a reference to A GlobalRoutePlannerDAO object. """ def __init__(self, dao): """ Constructor """ self._dao = dao self._topology = None self._graph = None self._id_map = None self._road_id_to_edge = None self._intersection_end_node = -1 self._previous_decision = RoadOption.VOID def setup(self): """ Performs initial server data lookup for detailed topology and builds graph representation of the world map. """ self._topology = self._dao.get_topology() self._graph, self._id_map, self._road_id_to_edge = self._build_graph() self._find_loose_ends() self._lane_change_link() def _build_graph(self): """ This function builds a networkx graph representation of topology. The topology is read from self._topology. graph node properties: vertex - (x,y,z) position in world map graph edge properties: entry_vector - unit vector along tangent at entry point exit_vector - unit vector along tangent at exit point net_vector - unit vector of the chord from entry to exit intersection - boolean indicating if the edge belongs to an intersection return : graph -> networkx graph representing the world map, id_map-> mapping from (x,y,z) to node id road_id_to_edge-> map from road id to edge in the graph """ graph = nx.DiGraph() id_map = dict() # Map with structure {(x,y,z): id, ... } road_id_to_edge = dict() # Map with structure {road_id: {lane_id: edge, ... }, ... } for segment in self._topology: entry_xyz, exit_xyz = segment['entryxyz'], segment['exitxyz'] path = segment['path'] entry_wp, exit_wp = segment['entry'], segment['exit'] intersection = entry_wp.is_junction road_id, section_id, lane_id = entry_wp.road_id, entry_wp.section_id, entry_wp.lane_id for vertex in entry_xyz, exit_xyz: # Adding unique nodes and populating id_map if vertex not in id_map: new_id = len(id_map) id_map[vertex] = new_id graph.add_node(new_id, vertex=vertex) n1 = id_map[entry_xyz] n2 = id_map[exit_xyz] if road_id not in road_id_to_edge: road_id_to_edge[road_id] = dict() if section_id not in road_id_to_edge[road_id]: road_id_to_edge[road_id][section_id] = dict() road_id_to_edge[road_id][section_id][lane_id] = (n1, n2) entry_carla_vector = entry_wp.transform.rotation.get_forward_vector() exit_carla_vector = exit_wp.transform.rotation.get_forward_vector() # Adding edge with attributes graph.add_edge( n1, n2, length=len(path) + 1, path=path, entry_waypoint=entry_wp, exit_waypoint=exit_wp, entry_vector=np.array( [entry_carla_vector.x, entry_carla_vector.y, entry_carla_vector.z]), exit_vector=np.array( [exit_carla_vector.x, exit_carla_vector.y, exit_carla_vector.z]), net_vector=vector(entry_wp.transform.location, exit_wp.transform.location), intersection=intersection, type=RoadOption.LANEFOLLOW) return graph, id_map, road_id_to_edge def _find_loose_ends(self): """ This method finds road segments that have an unconnected end, and adds them to the internal graph representation """ count_loose_ends = 0 hop_resolution = self._dao.get_resolution() for segment in self._topology: end_wp = segment['exit'] exit_xyz = segment['exitxyz'] road_id, section_id, lane_id = end_wp.road_id, end_wp.section_id, end_wp.lane_id if road_id in self._road_id_to_edge and section_id in self._road_id_to_edge[road_id] and lane_id in self._road_id_to_edge[road_id][section_id]: pass else: count_loose_ends += 1 if road_id not in self._road_id_to_edge: self._road_id_to_edge[road_id] = dict() if section_id not in self._road_id_to_edge[road_id]: self._road_id_to_edge[road_id][section_id] = dict() n1 = self._id_map[exit_xyz] n2 = -1*count_loose_ends self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2) next_wp = end_wp.next(hop_resolution) path = [] while next_wp is not None and next_wp and next_wp[0].road_id == road_id and next_wp[0].section_id == section_id and next_wp[0].lane_id == lane_id: path.append(next_wp[0]) next_wp = next_wp[0].next(hop_resolution) if path: n2_xyz = (path[-1].transform.location.x, path[-1].transform.location.y, path[-1].transform.location.z) self._graph.add_node(n2, vertex=n2_xyz) self._graph.add_edge( n1, n2, length=len(path) + 1, path=path, entry_waypoint=end_wp, exit_waypoint=path[-1], entry_vector=None, exit_vector=None, net_vector=None, intersection=end_wp.is_junction, type=RoadOption.LANEFOLLOW) def _localize(self, location): """ This function finds the road segment closest to given location location : carla.Location to be localized in the graph return : pair node ids representing an edge in the graph """ waypoint = self._dao.get_waypoint(location) edge = None try: edge = self._road_id_to_edge[waypoint.road_id][waypoint.section_id][waypoint.lane_id] except KeyError: print( "Failed to localize! : ", "Road id : ", waypoint.road_id, "Section id : ", waypoint.section_id, "Lane id : ", waypoint.lane_id, "Location : ", waypoint.transform.location.x, waypoint.transform.location.y) return edge def _lane_change_link(self): """ This method places zero cost links in the topology graph representing availability of lane changes. """ for segment in self._topology: left_found, right_found = False, False for waypoint in segment['path']: if not segment['entry'].is_junction: next_waypoint, next_road_option, next_segment = None, None, None if waypoint.right_lane_marking.lane_change & carla.LaneChange.Right and not right_found: next_waypoint = waypoint.get_right_lane() if next_waypoint is not None and next_waypoint.lane_type == carla.LaneType.Driving and waypoint.road_id == next_waypoint.road_id: next_road_option = RoadOption.CHANGELANERIGHT next_segment = self._localize(next_waypoint.transform.location) if next_segment is not None: self._graph.add_edge( self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint, exit_waypoint=next_waypoint, intersection=False, exit_vector=None, path=[], length=0, type=next_road_option, change_waypoint=next_waypoint) right_found = True if waypoint.left_lane_marking.lane_change & carla.LaneChange.Left and not left_found: next_waypoint = waypoint.get_left_lane() if next_waypoint is not None and next_waypoint.lane_type == carla.LaneType.Driving and waypoint.road_id == next_waypoint.road_id: next_road_option = RoadOption.CHANGELANELEFT next_segment = self._localize(next_waypoint.transform.location) if next_segment is not None: self._graph.add_edge( self._id_map[segment['entryxyz']], next_segment[0], entry_waypoint=waypoint, exit_waypoint=next_waypoint, intersection=False, exit_vector=None, path=[], length=0, type=next_road_option, change_waypoint=next_waypoint) left_found = True if left_found and right_found: break def _distance_heuristic(self, n1, n2): """ Distance heuristic calculator for path searching in self._graph """ l1 = np.array(self._graph.nodes[n1]['vertex']) l2 = np.array(self._graph.nodes[n2]['vertex']) return np.linalg.norm(l1-l2) def _path_search(self, origin, destination): """ This function finds the shortest path connecting origin and destination using A* search with distance heuristic. origin : carla.Location object of start position destination : carla.Location object of of end position return : path as list of node ids (as int) of the graph self._graph connecting origin and destination """ start, end = self._localize(origin), self._localize(destination) route = nx.astar_path( self._graph, source=start[0], target=end[0], heuristic=self._distance_heuristic, weight='length') route.append(end[1]) return route def _successive_last_intersection_edge(self, index, route): """ This method returns the last successive intersection edge from a starting index on the route. This helps moving past tiny intersection edges to calculate proper turn decisions. """ last_intersection_edge = None last_node = None for node1, node2 in [(route[i], route[i+1]) for i in range(index, len(route)-1)]: candidate_edge = self._graph.edges[node1, node2] if node1 == route[index]: last_intersection_edge = candidate_edge if candidate_edge['type'] == RoadOption.LANEFOLLOW and candidate_edge['intersection']: last_intersection_edge = candidate_edge last_node = node2 else: break return last_node, last_intersection_edge def _turn_decision(self, index, route, threshold=math.radians(35)): """ This method returns the turn decision (RoadOption) for pair of edges around current index of route list """ decision = None previous_node = route[index-1] current_node = route[index] next_node = route[index+1] next_edge = self._graph.edges[current_node, next_node] if index > 0: if self._previous_decision != RoadOption.VOID and self._intersection_end_node > 0 and self._intersection_end_node != previous_node and next_edge['type'] == RoadOption.LANEFOLLOW and next_edge['intersection']: decision = self._previous_decision else: self._intersection_end_node = -1 current_edge = self._graph.edges[previous_node, current_node] calculate_turn = current_edge['type'] == RoadOption.LANEFOLLOW and not current_edge[ 'intersection'] and next_edge['type'] == RoadOption.LANEFOLLOW and next_edge['intersection'] if calculate_turn: last_node, tail_edge = self._successive_last_intersection_edge(index, route) self._intersection_end_node = last_node if tail_edge is not None: next_edge = tail_edge cv, nv = current_edge['exit_vector'], next_edge['exit_vector'] if cv is None or nv is None: return next_edge['type'] cross_list = [] for neighbor in self._graph.successors(current_node): select_edge = self._graph.edges[current_node, neighbor] if select_edge['type'] == RoadOption.LANEFOLLOW: if neighbor != route[index+1]: sv = select_edge['net_vector'] cross_list.append(np.cross(cv, sv)[2]) next_cross = np.cross(cv, nv)[2] deviation = math.acos(np.clip( np.dot(cv, nv)/(np.linalg.norm(cv)*np.linalg.norm(nv)), -1.0, 1.0)) if not cross_list: cross_list.append(0) if deviation < threshold: decision = RoadOption.STRAIGHT elif cross_list and next_cross < min(cross_list): decision = RoadOption.LEFT elif cross_list and next_cross > max(cross_list): decision = RoadOption.RIGHT elif next_cross < 0: decision = RoadOption.LEFT elif next_cross > 0: decision = RoadOption.RIGHT else: decision = next_edge['type'] else: decision = next_edge['type'] self._previous_decision = decision return decision def abstract_route_plan(self, origin, destination): """ The following function generates the route plan based on origin : carla.Location object of the route's start position destination : carla.Location object of the route's end position return : list of turn by turn navigation decisions as agents.navigation.local_planner.RoadOption elements Possible values are STRAIGHT, LEFT, RIGHT, LANEFOLLOW, VOID CHANGELANELEFT, CHANGELANERIGHT """ route = self._path_search(origin, destination) plan = [] for i in range(len(route) - 1): road_option = self._turn_decision(i, route) plan.append(road_option) return plan def _find_closest_in_list(self, current_waypoint, waypoint_list): min_distance = float('inf') closest_index = -1 for i, waypoint in enumerate(waypoint_list): distance = waypoint.transform.location.distance( current_waypoint.transform.location) if distance < min_distance: min_distance = distance closest_index = i return closest_index def trace_route(self, origin, destination): """ This method returns list of (carla.Waypoint, RoadOption) from origin to destination """ route_trace = [] route = self._path_search(origin, destination) current_waypoint = self._dao.get_waypoint(origin) destination_waypoint = self._dao.get_waypoint(destination) resolution = self._dao.get_resolution() for i in range(len(route) - 1): road_option = self._turn_decision(i, route) edge = self._graph.edges[route[i], route[i+1]] path = [] if edge['type'] != RoadOption.LANEFOLLOW and edge['type'] != RoadOption.VOID: route_trace.append((current_waypoint, road_option)) exit_wp = edge['exit_waypoint'] n1, n2 = self._road_id_to_edge[exit_wp.road_id][exit_wp.section_id][exit_wp.lane_id] next_edge = self._graph.edges[n1, n2] if next_edge['path']: closest_index = self._find_closest_in_list(current_waypoint, next_edge['path']) closest_index = min(len(next_edge['path'])-1, closest_index+5) current_waypoint = next_edge['path'][closest_index] else: current_waypoint = next_edge['exit_waypoint'] route_trace.append((current_waypoint, road_option)) else: path = path + [edge['entry_waypoint']] + edge['path'] + [edge['exit_waypoint']] closest_index = self._find_closest_in_list(current_waypoint, path) for waypoint in path[closest_index:]: current_waypoint = waypoint route_trace.append((current_waypoint, road_option)) if len(route)-i <= 2 and waypoint.transform.location.distance(destination) < 2*resolution: break elif len(route)-i <= 2 and current_waypoint.road_id == destination_waypoint.road_id and current_waypoint.section_id == destination_waypoint.section_id and current_waypoint.lane_id == destination_waypoint.lane_id: destination_index = self._find_closest_in_list(destination_waypoint, path) if closest_index > destination_index: break return route_trace ================================================ FILE: agents/navigation/global_route_planner_dao.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides implementation for GlobalRoutePlannerDAO """ import numpy as np class GlobalRoutePlannerDAO(object): """ This class is the data access layer for fetching data from the carla server instance for GlobalRoutePlanner """ def __init__(self, wmap, sampling_resolution): """ Constructor method. :param wmap: carla.world object :param sampling_resolution: sampling distance between waypoints """ self._sampling_resolution = sampling_resolution self._wmap = wmap def get_topology(self): """ Accessor for topology. This function retrieves topology from the server as a list of road segments as pairs of waypoint objects, and processes the topology into a list of dictionary objects. :return topology: list of dictionary objects with the following attributes entry - waypoint of entry point of road segment entryxyz- (x,y,z) of entry point of road segment exit - waypoint of exit point of road segment exitxyz - (x,y,z) of exit point of road segment path - list of waypoints separated by 1m from entry to exit """ topology = [] # Retrieving waypoints to construct a detailed topology for segment in self._wmap.get_topology(): wp1, wp2 = segment[0], segment[1] l1, l2 = wp1.transform.location, wp2.transform.location # Rounding off to avoid floating point imprecision x1, y1, z1, x2, y2, z2 = np.round([l1.x, l1.y, l1.z, l2.x, l2.y, l2.z], 0) wp1.transform.location, wp2.transform.location = l1, l2 seg_dict = dict() seg_dict['entry'], seg_dict['exit'] = wp1, wp2 seg_dict['entryxyz'], seg_dict['exitxyz'] = (x1, y1, z1), (x2, y2, z2) seg_dict['path'] = [] endloc = wp2.transform.location if wp1.transform.location.distance(endloc) > self._sampling_resolution: w = wp1.next(self._sampling_resolution)[0] while w.transform.location.distance(endloc) > self._sampling_resolution: seg_dict['path'].append(w) w = w.next(self._sampling_resolution)[0] else: seg_dict['path'].append(wp1.next(self._sampling_resolution)[0]) topology.append(seg_dict) return topology def get_waypoint(self, location): """ The method returns waypoint at given location :param location: vehicle location :return waypoint: generated waypoint close to location """ waypoint = self._wmap.get_waypoint(location) return waypoint def get_resolution(self): """ Accessor for self._sampling_resolution """ return self._sampling_resolution ================================================ FILE: agents/navigation/local_planner.py ================================================ # Copyright (c) # Copyright (c) 2018-2020 CVC. # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains a local planner to perform low-level waypoint following based on PID controllers. """ from enum import Enum from collections import deque import random import carla from agents.navigation.controller import VehiclePIDController from agents.tools.misc import draw_waypoints class RoadOption(Enum): """ RoadOption represents the possible topological configurations when moving from a segment of lane to other. """ VOID = -1 LEFT = 1 RIGHT = 2 STRAIGHT = 3 LANEFOLLOW = 4 CHANGELANELEFT = 5 CHANGELANERIGHT = 6 class LocalPlanner(object): """ LocalPlanner implements the basic behavior of following a trajectory of waypoints that is generated on-the-fly. The low-level motion of the vehicle is computed by using two PID controllers, one is used for the lateral control and the other for the longitudinal control (cruise speed). When multiple paths are available (intersections) this local planner makes a random choice. """ # minimum distance to target waypoint as a percentage (e.g. within 90% of # total distance) MIN_DISTANCE_PERCENTAGE = 0.9 def __init__(self, vehicle, opt_dict=None): """ :param vehicle: actor to apply to local planner logic onto :param opt_dict: dictionary of arguments with the following semantics: dt -- time difference between physics control in seconds. This is typically fixed from server side using the arguments -benchmark -fps=F . In this case dt = 1/F target_speed -- desired cruise speed in Km/h sampling_radius -- search radius for next waypoints in seconds: e.g. 0.5 seconds ahead lateral_control_dict -- dictionary of arguments to setup the lateral PID controller {'K_P':, 'K_D':, 'K_I':, 'dt'} longitudinal_control_dict -- dictionary of arguments to setup the longitudinal PID controller {'K_P':, 'K_D':, 'K_I':, 'dt'} """ self._vehicle = vehicle self._map = self._vehicle.get_world().get_map() self._dt = None self._target_speed = None self._sampling_radius = None self._min_distance = None self._current_waypoint = None self._target_road_option = None self._next_waypoints = None self.target_waypoint = None self._vehicle_controller = None self._global_plan = None # queue with tuples of (waypoint, RoadOption) self._waypoints_queue = deque(maxlen=20000) self._buffer_size = 5 self._waypoint_buffer = deque(maxlen=self._buffer_size) # initializing controller self._init_controller(opt_dict) def __del__(self): if self._vehicle: self._vehicle.destroy() print("Destroying ego-vehicle!") def reset_vehicle(self): self._vehicle = None print("Resetting ego-vehicle!") def _init_controller(self, opt_dict): """ Controller initialization. :param opt_dict: dictionary of arguments. :return: """ # default params self._dt = 1.0 / 20.0 self._target_speed = 20.0 # Km/h self._sampling_radius = self._target_speed * 1 / 3.6 # 1 seconds horizon self._min_distance = self._sampling_radius * self.MIN_DISTANCE_PERCENTAGE self._max_brake = 0.3 self._max_throt = 0.75 self._max_steer = 0.8 args_lateral_dict = { 'K_P': 1.95, 'K_D': 0.2, 'K_I': 0.07, 'dt': self._dt} args_longitudinal_dict = { 'K_P': 1.0, 'K_D': 0, 'K_I': 0.05, 'dt': self._dt} # parameters overload if opt_dict: if 'dt' in opt_dict: self._dt = opt_dict['dt'] if 'target_speed' in opt_dict: self._target_speed = opt_dict['target_speed'] if 'sampling_radius' in opt_dict: self._sampling_radius = self._target_speed * \ opt_dict['sampling_radius'] / 3.6 if 'lateral_control_dict' in opt_dict: args_lateral_dict = opt_dict['lateral_control_dict'] if 'longitudinal_control_dict' in opt_dict: args_longitudinal_dict = opt_dict['longitudinal_control_dict'] if 'max_throttle' in opt_dict: self._max_throt = opt_dict['max_throttle'] if 'max_brake' in opt_dict: self._max_brake = opt_dict['max_brake'] if 'max_steering' in opt_dict: self._max_steer = opt_dict['max_steering'] self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location()) self._vehicle_controller = VehiclePIDController(self._vehicle, args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict, max_throttle=self._max_throt, max_brake=self._max_brake, max_steering=self._max_steer,) self._global_plan = False # compute initial waypoints self._waypoints_queue.append((self._current_waypoint.next(self._sampling_radius)[0], RoadOption.LANEFOLLOW)) self._target_road_option = RoadOption.LANEFOLLOW # fill waypoint trajectory queue self._compute_next_waypoints(k=200) def set_speed(self, speed): """ Request new target speed. :param speed: new target speed in Km/h :return: """ self._target_speed = speed def _compute_next_waypoints(self, k=1): """ Add new waypoints to the trajectory queue. :param k: how many waypoints to compute :return: """ # check we do not overflow the queue available_entries = self._waypoints_queue.maxlen - len(self._waypoints_queue) k = min(available_entries, k) for _ in range(k): last_waypoint = self._waypoints_queue[-1][0] next_waypoints = list(last_waypoint.next(self._sampling_radius)) if len(next_waypoints) == 0: break elif len(next_waypoints) == 1: # only one option available ==> lanefollowing next_waypoint = next_waypoints[0] road_option = RoadOption.LANEFOLLOW else: # random choice between the possible options road_options_list = _retrieve_options( next_waypoints, last_waypoint) road_option = random.choice(road_options_list) next_waypoint = next_waypoints[road_options_list.index( road_option)] self._waypoints_queue.append((next_waypoint, road_option)) def set_global_plan(self, current_plan): """ Resets the waypoint queue and buffer to match the new plan. Also sets the global_plan flag to avoid creating more waypoints :param current_plan: list of (carla.Waypoint, RoadOption) :return: """ # Reset the queue self._waypoints_queue.clear() for elem in current_plan: self._waypoints_queue.append(elem) self._target_road_option = RoadOption.LANEFOLLOW # and the buffer self._waypoint_buffer.clear() for _ in range(self._buffer_size): if self._waypoints_queue: self._waypoint_buffer.append( self._waypoints_queue.popleft()) else: break self._global_plan = True def run_step(self, debug=False): """ Execute one step of local planning which involves running the longitudinal and lateral PID controllers to follow the waypoints trajectory. :param debug: boolean flag to activate waypoints debugging :return: control to be applied """ # not enough waypoints in the horizon? => add more! if not self._global_plan and len(self._waypoints_queue) < int(self._waypoints_queue.maxlen * 0.5): self._compute_next_waypoints(k=100) if len(self._waypoints_queue) == 0 and len(self._waypoint_buffer) == 0: control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 1.0 control.hand_brake = False control.manual_gear_shift = False return control # Buffering the waypoints if not self._waypoint_buffer: for _ in range(self._buffer_size): if self._waypoints_queue: self._waypoint_buffer.append( self._waypoints_queue.popleft()) else: break # current vehicle waypoint vehicle_transform = self._vehicle.get_transform() self._current_waypoint = self._map.get_waypoint(vehicle_transform.location) # target waypoint self.target_waypoint, self._target_road_option = self._waypoint_buffer[0] # move using PID controllers control = self._vehicle_controller.run_step(self._target_speed, self.target_waypoint) # purge the queue of obsolete waypoints max_index = -1 for i, (waypoint, _) in enumerate(self._waypoint_buffer): if waypoint.transform.location.distance(vehicle_transform.location) < self._min_distance: max_index = i if max_index >= 0: for i in range(max_index + 1): self._waypoint_buffer.popleft() if debug: draw_waypoints(self._vehicle.get_world(), [self.target_waypoint], self._vehicle.get_location().z + 1.0) return control def done(self): """ Returns whether or not the planner has finished :return: boolean """ return len(self._waypoints_queue) == 0 and len(self._waypoint_buffer) == 0 def _retrieve_options(list_waypoints, current_waypoint): """ Compute the type of connection between the current active waypoint and the multiple waypoints present in list_waypoints. The result is encoded as a list of RoadOption enums. :param list_waypoints: list with the possible target waypoints in case of multiple options :param current_waypoint: current active waypoint :return: list of RoadOption enums representing the type of connection from the active waypoint to each candidate in list_waypoints """ options = [] for next_waypoint in list_waypoints: # this is needed because something we are linking to # the beggining of an intersection, therefore the # variation in angle is small next_next_waypoint = next_waypoint.next(3.0)[0] link = _compute_connection(current_waypoint, next_next_waypoint) options.append(link) return options def _compute_connection(current_waypoint, next_waypoint, threshold=35): """ Compute the type of topological connection between an active waypoint (current_waypoint) and a target waypoint (next_waypoint). :param current_waypoint: active waypoint :param next_waypoint: target waypoint :return: the type of topological connection encoded as a RoadOption enum: RoadOption.STRAIGHT RoadOption.LEFT RoadOption.RIGHT """ n = next_waypoint.transform.rotation.yaw n = n % 360.0 c = current_waypoint.transform.rotation.yaw c = c % 360.0 diff_angle = (n - c) % 180.0 if diff_angle < threshold or diff_angle > (180 - threshold): return RoadOption.STRAIGHT elif diff_angle > 90.0: return RoadOption.LEFT else: return RoadOption.RIGHT ================================================ FILE: agents/navigation/local_planner_behavior.py ================================================ #!/usr/bin/env python # Copyright (c) 2018 Intel Labs. # authors: German Ros (german.ros@intel.com) # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains a local planner to perform low-level waypoint following based on PID controllers. """ from collections import deque from enum import Enum import carla from agents.navigation.controller import VehiclePIDController from agents.tools.misc import distance_vehicle, draw_waypoints class RoadOption(Enum): """ RoadOption represents the possible topological configurations when moving from a segment of lane to other. """ VOID = -1 LEFT = 1 RIGHT = 2 STRAIGHT = 3 LANEFOLLOW = 4 CHANGELANELEFT = 5 CHANGELANERIGHT = 6 class LocalPlanner(object): """ LocalPlanner implements the basic behavior of following a trajectory of waypoints that is generated on-the-fly. The low-level motion of the vehicle is computed by using two PID controllers, one is used for the lateral control and the other for the longitudinal control (cruise speed). When multiple paths are available (intersections) this local planner makes a random choice. """ # Minimum distance to target waypoint as a percentage # (e.g. within 80% of total distance) # FPS used for dt FPS = 20 def __init__(self, agent): """ :param agent: agent that regulates the vehicle :param vehicle: actor to apply to local planner logic onto """ self._vehicle = agent.vehicle self._map = agent.vehicle.get_world().get_map() self._target_speed = None self.sampling_radius = None self._min_distance = None self._current_waypoint = None self.target_road_option = None self._next_waypoints = None self.target_waypoint = None self._vehicle_controller = None self._global_plan = None self._pid_controller = None self.waypoints_queue = deque(maxlen=20000) # queue with tuples of (waypoint, RoadOption) self._buffer_size = 5 self._waypoint_buffer = deque(maxlen=self._buffer_size) self._init_controller() # initializing controller def reset_vehicle(self): """Reset the ego-vehicle""" self._vehicle = None print("Resetting ego-vehicle!") def _init_controller(self): """ Controller initialization. dt -- time difference between physics control in seconds. This is can be fixed from server side using the arguments -benchmark -fps=F, since dt = 1/F target_speed -- desired cruise speed in km/h min_distance -- minimum distance to remove waypoint from queue lateral_dict -- dictionary of arguments to setup the lateral PID controller {'K_P':, 'K_D':, 'K_I':, 'dt'} longitudinal_dict -- dictionary of arguments to setup the longitudinal PID controller {'K_P':, 'K_D':, 'K_I':, 'dt'} """ # Default parameters self.args_lat_hw_dict = { 'K_P': 0.75, 'K_D': 0.02, 'K_I': 0.4, 'dt': 1.0 / self.FPS} self.args_lat_city_dict = { 'K_P': 0.58, 'K_D': 0.02, 'K_I': 0.5, 'dt': 1.0 / self.FPS} self.args_long_hw_dict = { 'K_P': 0.37, 'K_D': 0.024, 'K_I': 0.032, 'dt': 1.0 / self.FPS} self.args_long_city_dict = { 'K_P': 0.15, 'K_D': 0.05, 'K_I': 0.07, 'dt': 1.0 / self.FPS} self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location()) self._global_plan = False self._target_speed = self._vehicle.get_speed_limit() self._min_distance = 3 def set_speed(self, speed): """ Request new target speed. :param speed: new target speed in km/h """ self._target_speed = speed def set_global_plan(self, current_plan, clean=False): """ Sets new global plan. :param current_plan: list of waypoints in the actual plan """ for elem in current_plan: self.waypoints_queue.append(elem) if clean: self._waypoint_buffer.clear() for _ in range(self._buffer_size): if self.waypoints_queue: self._waypoint_buffer.append( self.waypoints_queue.popleft()) else: break self._global_plan = True def get_incoming_waypoint_and_direction(self, steps=3): """ Returns direction and waypoint at a distance ahead defined by the user. :param steps: number of steps to get the incoming waypoint. """ if len(self.waypoints_queue) > steps: return self.waypoints_queue[steps] else: try: wpt, direction = self.waypoints_queue[-1] return wpt, direction except IndexError as i: print(i) return None, RoadOption.VOID return None, RoadOption.VOID def run_step(self, target_speed=None, debug=False): """ Execute one step of local planning which involves running the longitudinal and lateral PID controllers to follow the waypoints trajectory. :param target_speed: desired speed :param debug: boolean flag to activate waypoints debugging :return: control """ if target_speed is not None: self._target_speed = target_speed else: self._target_speed = self._vehicle.get_speed_limit() if len(self.waypoints_queue) == 0: control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 1.0 control.hand_brake = False control.manual_gear_shift = False return control # Buffering the waypoints if not self._waypoint_buffer: for i in range(self._buffer_size): if self.waypoints_queue: self._waypoint_buffer.append( self.waypoints_queue.popleft()) else: break # Current vehicle waypoint self._current_waypoint = self._map.get_waypoint(self._vehicle.get_location()) # Target waypoint self.target_waypoint, self.target_road_option = self._waypoint_buffer[0] if target_speed > 50: args_lat = self.args_lat_hw_dict args_long = self.args_long_hw_dict else: args_lat = self.args_lat_city_dict args_long = self.args_long_city_dict self._pid_controller = VehiclePIDController(self._vehicle, args_lateral=args_lat, args_longitudinal=args_long) control = self._pid_controller.run_step(self._target_speed, self.target_waypoint) # Purge the queue of obsolete waypoints vehicle_transform = self._vehicle.get_transform() max_index = -1 for i, (waypoint, _) in enumerate(self._waypoint_buffer): if distance_vehicle( waypoint, vehicle_transform) < self._min_distance: max_index = i if max_index >= 0: for i in range(max_index + 1): self._waypoint_buffer.popleft() if debug: draw_waypoints(self._vehicle.get_world(), [self.target_waypoint], 1.0) return control ================================================ FILE: agents/navigation/roaming_agent.py ================================================ #!/usr/bin/env python # Copyright (c) 2018 Intel Labs. # authors: German Ros (german.ros@intel.com) # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module implements an agent that roams around a track following random waypoints and avoiding other vehicles. The agent also responds to traffic lights. """ from agents.navigation.agent import Agent, AgentState from agents.navigation.local_planner import LocalPlanner class RoamingAgent(Agent): """ RoamingAgent implements a basic agent that navigates scenes making random choices when facing an intersection. This agent respects traffic lights and other vehicles. """ def __init__(self, vehicle): """ :param vehicle: actor to apply to local planner logic onto """ super(RoamingAgent, self).__init__(vehicle) self._proximity_threshold = 10.0 # meters self._state = AgentState.NAVIGATING self._local_planner = LocalPlanner(self._vehicle) def run_step(self, debug=False): """ Execute one step of navigation. :return: carla.VehicleControl """ # is there an obstacle in front of us? hazard_detected = False # retrieve relevant elements for safe navigation, i.e.: traffic lights # and other vehicles actor_list = self._world.get_actors() vehicle_list = actor_list.filter("*vehicle*") lights_list = actor_list.filter("*traffic_light*") # check possible obstacles vehicle_state, vehicle = self._is_vehicle_hazard(vehicle_list) if vehicle_state: if debug: print('!!! VEHICLE BLOCKING AHEAD [{}])'.format(vehicle.id)) self._state = AgentState.BLOCKED_BY_VEHICLE hazard_detected = True # check for the state of the traffic lights light_state, traffic_light = self._is_light_red(lights_list) if light_state: if debug: print('=== RED LIGHT AHEAD [{}])'.format(traffic_light.id)) self._state = AgentState.BLOCKED_RED_LIGHT hazard_detected = True if hazard_detected: control = self.emergency_stop() else: self._state = AgentState.NAVIGATING # standard local planner behavior control = self._local_planner.run_step() return control ================================================ FILE: agents/navigation/types_behavior.py ================================================ # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains the different parameters sets for each behavior. """ class Cautious(object): """Class for Cautious agent.""" max_speed = 40 speed_lim_dist = 6 speed_decrease = 12 safety_time = 3 min_proximity_threshold = 12 braking_distance = 6 overtake_counter = -1 tailgate_counter = 0 class Normal(object): """Class for Normal agent.""" max_speed = 50 speed_lim_dist = 3 speed_decrease = 10 safety_time = 3 min_proximity_threshold = 10 braking_distance = 5 overtake_counter = 0 tailgate_counter = 0 class Aggressive(object): """Class for Aggressive agent.""" max_speed = 70 speed_lim_dist = 1 speed_decrease = 8 safety_time = 3 min_proximity_threshold = 8 braking_distance = 4 overtake_counter = 0 tailgate_counter = -1 ================================================ FILE: agents/tools/__init__.py ================================================ ================================================ FILE: agents/tools/misc.py ================================================ #!/usr/bin/env python # Copyright (c) 2018 Intel Labs. # authors: German Ros (german.ros@intel.com) # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Module with auxiliary functions. """ import math import numpy as np import carla def draw_waypoints(world, waypoints, z=0.5): """ Draw a list of waypoints at a certain height given in z. :param world: carla.world object :param waypoints: list or iterable container with the waypoints to draw :param z: height in meters """ for wpt in waypoints: wpt_t = wpt.transform begin = wpt_t.location + carla.Location(z=z) angle = math.radians(wpt_t.rotation.yaw) end = begin + carla.Location(x=math.cos(angle), y=math.sin(angle)) world.debug.draw_arrow(begin, end, arrow_size=0.3, life_time=1.0) def get_speed(vehicle): """ Compute speed of a vehicle in Km/h. :param vehicle: the vehicle for which speed is calculated :return: speed as a float in Km/h """ vel = vehicle.get_velocity() return 3.6 * math.sqrt(vel.x ** 2 + vel.y ** 2 + vel.z ** 2) def is_within_distance_ahead(target_transform, current_transform, max_distance): """ Check if a target object is within a certain distance in front of a reference object. :param target_transform: location of the target object :param current_transform: location of the reference object :param orientation: orientation of the reference object :param max_distance: maximum allowed distance :return: True if target object is within max_distance ahead of the reference object """ target_vector = np.array([target_transform.location.x - current_transform.location.x, target_transform.location.y - current_transform.location.y]) norm_target = np.linalg.norm(target_vector) # If the vector is too short, we can simply stop here if norm_target < 0.001: return True if norm_target > max_distance: return False fwd = current_transform.get_forward_vector() forward_vector = np.array([fwd.x, fwd.y]) d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.))) return d_angle < 90.0 def is_within_distance(target_location, current_location, orientation, max_distance, d_angle_th_up, d_angle_th_low=0): """ Check if a target object is within a certain distance from a reference object. A vehicle in front would be something around 0 deg, while one behind around 180 deg. :param target_location: location of the target object :param current_location: location of the reference object :param orientation: orientation of the reference object :param max_distance: maximum allowed distance :param d_angle_th_up: upper thereshold for angle :param d_angle_th_low: low thereshold for angle (optional, default is 0) :return: True if target object is within max_distance ahead of the reference object """ target_vector = np.array([target_location.x - current_location.x, target_location.y - current_location.y]) norm_target = np.linalg.norm(target_vector) # If the vector is too short, we can simply stop here if norm_target < 0.001: return True if norm_target > max_distance: return False forward_vector = np.array( [math.cos(math.radians(orientation)), math.sin(math.radians(orientation))]) d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.))) return d_angle_th_low < d_angle < d_angle_th_up def compute_magnitude_angle(target_location, current_location, orientation): """ Compute relative angle and distance between a target_location and a current_location :param target_location: location of the target object :param current_location: location of the reference object :param orientation: orientation of the reference object :return: a tuple composed by the distance to the object and the angle between both objects """ target_vector = np.array([target_location.x - current_location.x, target_location.y - current_location.y]) norm_target = np.linalg.norm(target_vector) forward_vector = np.array([math.cos(math.radians(orientation)), math.sin(math.radians(orientation))]) d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.))) return (norm_target, d_angle) def distance_vehicle(waypoint, vehicle_transform): """ Returns the 2D distance from a waypoint to a vehicle :param waypoint: actual waypoint :param vehicle_transform: transform of the target vehicle """ loc = vehicle_transform.location x = waypoint.transform.location.x - loc.x y = waypoint.transform.location.y - loc.y return math.sqrt(x * x + y * y) def vector(location_1, location_2): """ Returns the unit vector from location_1 to location_2 :param location_1, location_2: carla.Location objects """ x = location_2.x - location_1.x y = location_2.y - location_1.y z = location_2.z - location_1.z norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps return [x / norm, y / norm, z / norm] def compute_distance(location_1, location_2): """ Euclidean distance between 3D points :param location_1, location_2: 3D points """ x = location_2.x - location_1.x y = location_2.y - location_1.y z = location_2.z - location_1.z norm = np.linalg.norm([x, y, z]) + np.finfo(float).eps return norm def positive(num): """ Return the given number if positive, else 0 :param num: value to check """ return num if num > 0.0 else 0.0 ================================================ FILE: camera_calibration/README.md ================================================ # Camera Calibration Under the current setting, all four cameras have **fov 150**. If you want to change their fov, you could use the following code to estimate the corresponding distortion parameters. More discussions here: https://github.com/carla-simulator/carla/issues/3412. 1. Build Carla from source code with commit 0c97e9a5de5b35b759cc5b0955801244ed76791f: - git clone the latest commit - git checkout -b branch_id commit_id - following the guidance in https://carla.readthedocs.io/en/0.9.10/build_linux/ - make launch (so that the Carla is opened with an UE4 editor) Note that the Carla built from source and its cooresponding environment (Python, environment variables, etc) are only used for estimating the distortion parameters. In all other experiments, we use the official pre-build version 0.9.10.1 and the environment under our setting. If there is any problem during building the Carla, please refer to https://carla.readthedocs.io/en/0.9.10/build_linux/. 2. Conduct Checkboard Calibration - Download the checkboard asset for Carla Town3 https://github.com/AbanobSoliman/IBISCape and put it in the suggested folder of Carla from source - In the Carla UE4 editor, click make launch -> Compile -> Build -> Play - **python collect_data_for_calibration.py** (sensor setting) to collect image for calibration (For more information about the data collecting process, please refer to tutorials about checkboard camera calibration: https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html and the instruction in the original code https://github.com/AbanobSoliman/IBISCape) - **python calculate_distortion_parameters.py** (line 26-35 to calculate intrinsic matrix, line 32 to select image index for calibration) to output distortion matrix - Put an image collected by your Carla into this folded and rename it as "test.png". - **python undistort.py** (line 4-10 to set intrinsics matrix, line 14 to input the distortion matrix from the last step) to verify the effectiveness of the undistortion. Note that the Tangential Distortion effects need extra attention when collect images. ## Images without Distortion If your application does not involve official benchmarks such town05Long, Longest6 or Leaderboard, you could eliminate all distortions. In [leaderboard/leaderboard/autoagents/agent_wrapper.py](../leaderboard/leaderboard/autoagents/agent_wrapper.py), set all *lens_circle_multiplier* to 0.0, all *lens_circle_falloff* to 5.0, and all *chromatic_aberration_intensity* to 0.0. Reference: https://carla.readthedocs.io/en/latest/ref_sensors/ ## Acknowledgements The calibration code is based on [IBISCape](https://github.com/AbanobSoliman/IBISCape) and please check out their awsome code. ================================================ FILE: camera_calibration/calculate_distortion_parameters.py ================================================ #!/usr/bin/env python import cv2 import numpy as np import os import glob # Defining the dimensions of checkerboard CHECKERBOARD = (7, 7) criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001) # Creating vector to store vectors of 3D points for each checkerboard image objpoints = [] # Creating vector to store vectors of 2D points for each checkerboard image imgpoints = [] # Defining the world coordinates for 3D points objp = np.zeros((1, CHECKERBOARD[0] * CHECKERBOARD[1], 3), np.float32) objp[0,:,:2] = np.mgrid[0:CHECKERBOARD[0], 0:CHECKERBOARD[1]].T.reshape(-1, 2) prev_img_shape = None # Extracting path of individual image stored in a given directory img_path = None print("Image Path:", img_path, "(Please Change it to your path of Carla **built from source**!!!)") images = glob.glob(img_path+'/*.png') ImageSizeX = 1600 ImageSizeY = 900 CameraFOV = 150 f = ImageSizeX /(2 * np.tan(CameraFOV * np.pi / 360)) Cx = ImageSizeX / 2 Cy = ImageSizeY / 2 # intrinsics = np.array([[214.35935394, 0, 800, ], # [ 0, 214.35935394, 450, ], # [ 0, 0, 1, ]]) intrinsics = np.array([[f, 0, Cx], [0, f, Cy], [0, 0, 1 ]]) print(intrinsics) for fname in images: index = int() if fname[:-4].split("/")[-1][-4:] < "8028" or fname[:-4].split("/")[-1][-4:] > "8068": continue img = cv2.imread(fname) gray = cv2.cvtColor(img,cv2.COLOR_BGR2GRAY) # Find the chess board corners # If desired number of corners are found in the image then ret = true ret, corners = cv2.findChessboardCorners(gray, CHECKERBOARD, cv2.CALIB_CB_ADAPTIVE_THRESH + cv2.CALIB_CB_NORMALIZE_IMAGE + cv2.CALIB_CB_FAST_CHECK) """ If desired number of corner are detected, we refine the pixel coordinates and display them on the images of checker board """ print(fname, ret) if ret == True: objpoints.append(objp) # refining pixel coordinates for given 2d points. corners2 = cv2.cornerSubPix(gray, corners, (11,11),(-1,-1), criteria) imgpoints.append(corners2) # Draw and display the corners img = cv2.drawChessboardCorners(img, CHECKERBOARD, corners2, ret) # cv2.imshow('img',img) # cv2.waitKey(0) cv2.destroyAllWindows() h,w = img.shape[:2] """ Performing camera calibration by passing the value of known 3D points (objpoints) and corresponding pixel coordinates of the detected corners (imgpoints) """ ret, mtx, dist, rvecs, tvecs = cv2.calibrateCamera(objpoints, imgpoints, gray.shape[::-1], intrinsics, None, flags=cv2.CALIB_FIX_INTRINSIC+cv2.CALIB_FIX_PRINCIPAL_POINT) print("Camera matrix : \n") print(mtx) print("Distortion Matrix : \n") print(dist) print("rvecs : \n") print(rvecs) print("tvecs : \n") print(tvecs) ================================================ FILE: camera_calibration/collect_data_for_calibration.py ================================================ #!/usr/bin/env python # Copyright (c) 2021 IBISC Laborartory, Pelvoux, France # This work is licensed under the terms of the MIT license. # For a copy, see . ##From https://github.com/AbanobSoliman/IBISCape import random import glob import os import sys import csv ####Please Change it to your path of Carla **built from source** egg_path = None print("Egg Path:", egg_path, "(Please Change it to your path of Carla **built from source**!!!)") sys.path.append(glob.glob(egg_path)[0]) import cv2 import carla from carla import ColorConverter as cc import argparse import collections import datetime import logging import math import random import re import weakref try: import pygame from pygame.locals import KMOD_CTRL from pygame.locals import KMOD_SHIFT from pygame.locals import K_0 from pygame.locals import K_9 from pygame.locals import K_BACKQUOTE from pygame.locals import K_BACKSPACE from pygame.locals import K_COMMA from pygame.locals import K_DOWN from pygame.locals import K_ESCAPE from pygame.locals import K_F1 from pygame.locals import K_LEFT from pygame.locals import K_PERIOD from pygame.locals import K_RIGHT from pygame.locals import K_SLASH from pygame.locals import K_SPACE from pygame.locals import K_TAB from pygame.locals import K_UP from pygame.locals import K_a from pygame.locals import K_b from pygame.locals import K_c from pygame.locals import K_d from pygame.locals import K_g from pygame.locals import K_h from pygame.locals import K_i from pygame.locals import K_l from pygame.locals import K_m from pygame.locals import K_n from pygame.locals import K_p from pygame.locals import K_k from pygame.locals import K_j from pygame.locals import K_q from pygame.locals import K_r from pygame.locals import K_s from pygame.locals import K_v from pygame.locals import K_w from pygame.locals import K_x from pygame.locals import K_z from pygame.locals import K_MINUS from pygame.locals import K_EQUALS except ImportError: raise RuntimeError( 'cannot import pygame, make sure pygame package is installed') try: import numpy as np except ImportError: raise RuntimeError( 'cannot import numpy, make sure numpy package is installed') try: import queue except ImportError: import Queue as queue import time import subprocess client = carla.Client('localhost', 2000) client.set_timeout(20.0) # ============================================================================== # -- Creating the World -------------------------------------------------------- # ============================================================================== global world global m world = client.get_world() m = world.get_map() self = world self.recording = False # ============================================================================== # -- Output files Handling------------------------------------------------------ # ============================================================================== try: parent_dir = os.getcwd() path1 = os.path.join(parent_dir, "RGBD_Calib_i_%s" % (m.name)) os.mkdir(path1) path4 = os.path.join(path1, "rgb") os.mkdir(path4) path8 = os.path.join(path4, "frames") os.mkdir(path8) path12 = os.path.join(path1, "depth") os.mkdir(path12) path15 = os.path.join(path12, "frames") os.mkdir(path15) path10 = os.path.join(path1, "other_sensors") os.mkdir(path10) path11 = os.path.join(path1, "vehicle_gt") os.mkdir(path11) except OSError: print("Creation of the directory %s failed" % path1) print("Creation of the directory %s failed" % path4) print("Creation of the directory %s failed" % path8) print("Creation of the directory %s failed" % path10) print("Creation of the directory %s failed" % path11) print("Creation of the directory %s failed" % path12) print("Creation of the directory %s failed" % path15) else: print("Successfully created the directory %s " % path1) print("Successfully created the directory %s " % path4) print("Successfully created the directory %s " % path8) print("Successfully created the directory %s " % path10) print("Successfully created the directory %s " % path11) print("Successfully created the directory %s " % path12) print("Successfully created the directory %s " % path15) file_rgb = open(os.path.join(path4, 'timestamps.csv'), "a") file_depth = open(os.path.join(path12, 'timestamps.csv'), "a") file_groundtruth_sync = open(os.path.join(path11, 'groundtruth_sync.csv'), "a") file_GNSS = open(os.path.join(path10, 'gnss.csv'), "a") writer0 = csv.writer(file_rgb, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL) writer0.writerow(['#timestamp [ns]', 'filename']) writer8 = csv.writer(file_depth, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL) writer8.writerow(['#timestamp [ns]', 'filename']) writer4 = csv.writer(file_groundtruth_sync, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL) writer4.writerow(['#timestamp [ns]', 'p_RS_R_x_m_', 'p_RS_R_y_m_', 'p_RS_R_z_m_', 'v_RS_R_x_mS__1_', 'v_RS_R_y_mS__1_', 'v_RS_R_z_mS__1_', 'a_RS_S_x_mS__2_', 'a_RS_S_y_mS__2_', 'a_RS_S_z_mS__2_', 'q_RS_w__', 'q_RS_x__', 'q_RS_y__', 'q_RS_z__', 'w_RS_S_x_radS__1_', 'w_RS_S_y_radS__1_', 'w_RS_S_z_radS__1_']) writer5 = csv.writer(file_GNSS, delimiter=',', quotechar='|', quoting=csv.QUOTE_MINIMAL) writer5.writerow(['#timestamp [ns]', 'latitude', 'longitude', 'altitude']) # ============================================================================== # -- GnssSensor ---------------------------------------------------------------- # ============================================================================== class gnssSensor(object): def __init__(self, parent_actor): self.sensor = None self._parent = parent_actor self.lat = 0.0 self.lon = 0.0 world = self._parent.get_world() bp = world.get_blueprint_library().find('sensor.other.gnss') bp.set_attribute('noise_alt_bias', '0.0') bp.set_attribute('noise_lat_bias', '0.0') bp.set_attribute('noise_lon_bias', '0.0') bp.set_attribute('noise_alt_stddev', '0.0') bp.set_attribute('noise_lat_stddev', '0.0') bp.set_attribute('noise_lon_stddev', '0.0') bp.set_attribute('noise_seed', '0') bp.set_attribute('sensor_tick', '0.05') self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location( x=-0.2, y=0, z=2.8), carla.Rotation(pitch=0, roll=0, yaw=0)), attach_to=self._parent, attachment_type=carla.AttachmentType.Rigid) # We need to pass the lambda a weak reference to self to avoid circular # reference. weak_self = weakref.ref(self) self.sensor.listen( lambda event: gnssSensor._on_gnss_event(weak_self, event)) @staticmethod def _on_gnss_event(weak_self, event): self = weak_self() if not self: return self.lat = event.latitude self.lon = event.longitude self.alt = event.altitude self.tmp = event.timestamp def destroy(self): self.sensor.stop() self.sensor.destroy() # ============================================================================== # -- Useful Functions----------------------------------------------------------- # ============================================================================== def resize_img(img): scale_percent = 50 # percent of original size width = int(img.shape[1] * scale_percent / 100) height = int(img.shape[0] * scale_percent / 100) dim = (width, height) # resize image resized = cv2.resize(img, dim, interpolation = cv2.INTER_AREA) return resized def euler_to_quaternion(yaw, pitch, roll): qx = np.sin(roll/2) * np.cos(pitch/2) * np.cos(yaw/2) - np.cos(roll/2) * np.sin(pitch/2) * np.sin(yaw/2) qy = np.cos(roll/2) * np.sin(pitch/2) * np.cos(yaw/2) + np.sin(roll/2) * np.cos(pitch/2) * np.sin(yaw/2) qz = np.cos(roll/2) * np.cos(pitch/2) * np.sin(yaw/2) - np.sin(roll/2) * np.sin(pitch/2) * np.cos(yaw/2) qw = np.cos(roll/2) * np.cos(pitch/2) * np.cos(yaw/2) + np.sin(roll/2) * np.sin(pitch/2) * np.sin(yaw/2) quat = [qw, qx, qy, qz] return quat/np.linalg.norm(quat) def draw_rgb_image(surface, image_rgb): array = np.frombuffer(image_rgb.raw_data, dtype=np.dtype("uint8")) array = np.reshape(array, (image_rgb.height, image_rgb.width, 4)) array = array[:, :, :3] array = array[:, :, ::-1] image_surface = pygame.surfarray.make_surface(resize_img(array.swapaxes(0, 1))) # image_surface.set_alpha(100) surface.blit(image_surface, (0, 0)) def draw_depth_image(surface, image_depth): array = np.frombuffer(image_depth.raw_data, dtype=np.dtype("uint8")) array = np.reshape(array, (image_depth.height, image_depth.width, 4)) array = array[:, :, :3] array = array[:, :, ::-1] image_surface = pygame.surfarray.make_surface(resize_img(array.swapaxes(0, 1))) # image_surface.set_alpha(100) surface.blit(image_surface, (1000, 0)) def get_font(): fonts = [x for x in pygame.font.get_fonts()] default_font = 'ubuntumono' font = default_font if default_font in fonts else fonts[0] font = pygame.font.match_font(font) return pygame.font.Font(font, 14) def create_main_actors(start_pose, waypoint): blueprint_library = world.get_blueprint_library() vehicle = world.spawn_actor( blueprint_library.filter('vehicle')[1], start_pose) vehicle.set_simulate_physics(True) vehicle.set_transform(waypoint.transform) bp_rgb = blueprint_library.find('sensor.camera.rgb') fov = "150.0" print("Current Fov:", fov, "Please Change it to your deisred fov!") # Modify the basic attributes of the blueprint bp_rgb.set_attribute('image_size_x', '1600') bp_rgb.set_attribute('image_size_y', '900') bp_rgb.set_attribute('sensor_tick', '0.05') bp_rgb.set_attribute('bloom_intensity', '0.675') bp_rgb.set_attribute('fov', fov) bp_rgb.set_attribute('fstop', '1.4') bp_rgb.set_attribute('iso', '100.0') bp_rgb.set_attribute('gamma', '2.2') bp_rgb.set_attribute('lens_flare_intensity', '0.1') bp_rgb.set_attribute('shutter_speed', '200.0') # Modify the lens distortion attributes bp_rgb.set_attribute('chromatic_aberration_intensity', '0.5') bp_rgb.set_attribute('chromatic_aberration_offset', '0.0') bp_rgb.set_attribute('lens_circle_falloff', '3.0') bp_rgb.set_attribute('lens_circle_multiplier', '3.0') bp_rgb.set_attribute('lens_k', '-1.0') bp_rgb.set_attribute('lens_kcube', '0.0') bp_rgb.set_attribute('lens_x_size', '0.08') bp_rgb.set_attribute('lens_y_size', '0.08') camera_rgb = world.spawn_actor( bp_rgb, carla.Transform(carla.Location(x=1.3, y=0.0, z=2.5), carla.Rotation(pitch=0.0, roll=0.0, yaw=0.0)), attach_to=vehicle, attachment_type=carla.AttachmentType.Rigid) bp_depth = blueprint_library.find('sensor.camera.depth') # Modify the basic attributes of the blueprint bp_depth.set_attribute('image_size_x', '160') bp_depth.set_attribute('image_size_y', '90') bp_depth.set_attribute('fov', fov) bp_depth.set_attribute('sensor_tick', '0.05') # Modify the lens distortion attributes bp_depth.set_attribute('lens_circle_falloff', '5.0') bp_depth.set_attribute('lens_circle_multiplier', '0.0') bp_depth.set_attribute('lens_k', '-1.0') bp_depth.set_attribute('lens_kcube', '0.0') bp_depth.set_attribute('lens_x_size', '0.08') bp_depth.set_attribute('lens_y_size', '0.08') camera_depth = world.spawn_actor( bp_depth, carla.Transform(carla.Location(x=0.0, y=0.0, z=2.8), carla.Rotation(pitch=0.0, roll=0.0, yaw=0.0)), attach_to=vehicle, attachment_type=carla.AttachmentType.Rigid) Gnss_sensor = gnssSensor(vehicle) return vehicle, camera_rgb, camera_depth, Gnss_sensor def get_actor_display_name(actor, truncate=250): name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:]) return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name def _RGB_sensor_callback(sensor_data, ts, display): draw_rgb_image(display, sensor_data) if self.recording: sensor_data.save_to_disk('RGBD_Calib_i_%s/rgb/frames/%d.png' % (m.name, ts)) file_rgb.write("%d,%d.png \n" % (ts, ts)) def _DEPTH_sensor_callback(sensor_data, ts, display): sensor_data.convert(cc.LogarithmicDepth) draw_depth_image(display, sensor_data) if self.recording: sensor_data.save_to_disk('RGBD_Calib_i_%s/depth/frames/%d.png' % (m.name, ts)) file_depth.write("%d,%d.png \n" % (ts, ts)) # ============================================================================== # -- Sensor Synchronization----------------------------------------------------- # ============================================================================== class CarlaSyncMode(object): """ Context manager to synchronize output from different sensors. Synchronous mode is enabled as long as we are inside this context with CarlaSyncMode(world, sensors) as sync_mode: while True: data = sync_mode.tick(timeout=1.0) """ def __init__(self, world, *sensors, **kwargs): self.world = world self.sensors = sensors self.frame = None self.delta_seconds = 1.0 / kwargs.get('fps', 20) self._queues = [] self._settings = None def __enter__(self): self._settings = self.world.get_settings() self.frame = self.world.apply_settings(carla.WorldSettings( no_rendering_mode=False, synchronous_mode=True, fixed_delta_seconds=self.delta_seconds)) def make_queue(register_event): q = queue.Queue() register_event(q.put) self._queues.append(q) make_queue(self.world.on_tick) for sensor in self.sensors: make_queue(sensor.listen) return self def tick(self, timeout): self.frame = self.world.tick() data = [self._retrieve_data(q, timeout) for q in self._queues] assert all(x.frame == self.frame for x in data) return data def __exit__(self, *args, **kwargs): self.world.apply_settings(self._settings) def _retrieve_data(self, sensor_queue, timeout): while True: data = sensor_queue.get(timeout=timeout) if data.frame == self.frame: return data # ============================================================================== # -- Main Function-------------------------------------------------------------- # ============================================================================== def main(): actor_list = [] pygame.init() pygame.display.set_caption( 'IBISCape: Multi-modal Data Acquisition Framework') display = pygame.display.set_mode( (1200, 450), pygame.HWSURFACE | pygame.DOUBLEBUF) font = get_font() clock = pygame.time.Clock() iterator = 1 rvrs = False hand_brake = False try: start_Pose = m.get_spawn_points() start_pose = start_Pose[32] waypoint = m.get_waypoint(start_pose.location) vehicle, camera_rgb, camera_depth, Gnss_sensor = create_main_actors(start_pose, waypoint) file_veh_sim = open(os.path.join(path11, '%s_simulation.txt' % get_actor_display_name(vehicle, truncate=200)), "a") file_associate = open(os.path.join(path11, 'association.txt'),"a") actor_list.append(vehicle) actor_list.append(camera_rgb) actor_list.append(camera_depth) actor_list.append(Gnss_sensor) # Create a synchronous mode context. with CarlaSyncMode(world, camera_rgb, camera_depth, fps=20) as sync_mode: while True: for event in pygame.event.get(): if event.type == pygame.QUIT: pygame.quit() elif event.type == pygame.KEYDOWN: if event.key == K_r: self.recording = not self.recording elif event.key == K_q: rvrs = not rvrs elif event.key == K_SPACE: vehicle.disable_constant_velocity() vehicle.apply_control( carla.VehicleControl(hand_brake=not hand_brake)) elif event.key == K_w: if rvrs: vehicle.apply_control( carla.VehicleControl(reverse=True, brake=0.0)) vehicle.enable_constant_velocity( carla.Vector3D(-3, 0, 0)) else: vehicle.apply_control( carla.VehicleControl(throttle=1.0, brake=0.0)) vehicle.enable_constant_velocity( carla.Vector3D(3, 0, 0)) elif event.key == K_s: vehicle.disable_constant_velocity() vehicle.apply_control( carla.VehicleControl(throttle=0.0, brake=1.0)) elif event.key == K_a: vehicle.apply_control( carla.VehicleControl(steer=-1.0)) elif event.key == K_d: vehicle.apply_control( carla.VehicleControl(steer=1.0)) elif event.key == pygame.K_ESCAPE: return elif event.type == pygame.KEYUP: if event.key == K_a: vehicle.apply_control( carla.VehicleControl(steer=0.0)) elif event.key == K_d: vehicle.apply_control( carla.VehicleControl(steer=0.0)) clock.tick() # Advance the simulation and wait for the data. snapshot, image_rgb, image_depth = sync_mode.tick( timeout=2.0) Pose = vehicle.get_transform() Accl = vehicle.get_acceleration() velo = vehicle.get_velocity() AngV = vehicle.get_angular_velocity() Ctrl = vehicle.get_control() t_world = snapshot.timestamp.elapsed_seconds*(10**9) fps = round(1.0 / snapshot.timestamp.delta_seconds) # Draw the display. _RGB_sensor_callback(image_rgb, t_world, display) _DEPTH_sensor_callback(image_depth, t_world, display) if self.recording: file_GNSS.write("%f,%21.21f,%21.21f,%21.21f \n" % (t_world, Gnss_sensor.lat, Gnss_sensor.lon, Gnss_sensor.alt)) quat = euler_to_quaternion(math.radians(Pose.rotation.yaw), math.radians(Pose.rotation.pitch), math.radians(Pose.rotation.roll)) file_groundtruth_sync.write("%d,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f,%21.21f \n" % (t_world, Pose.location.x, Pose.location.y, Pose.location.z, velo.x, velo.y, velo.z, Accl.x, Accl.y, Accl.z, quat[0], quat[1], quat[2], quat[3], math.radians(AngV.x), math.radians(AngV.y), math.radians(AngV.z))) file_veh_sim.write("%d,%f,%f,%f \n" % ( t_world, Ctrl.throttle, Ctrl.steer, Ctrl.brake)) file_associate.write("%d rgb/%d.png %d depth/%d.png \n" %(t_world,t_world,t_world,t_world)) display.blit(font.render('Calibration Frame Number: %d' % ( iterator), True, (250, 0, 0)), (50, 208)) iterator += 1 display.blit( font.render('% 5d FPS (real)' % clock.get_fps(), True, (250, 0, 0)), (8, 10)) display.blit( font.render('% 5d FPS (simulated)' % fps, True, (250, 0, 0)), (8, 28)) display.blit(font.render('Recording %s' % ( 'On' if self.recording else 'Off - Press R Key to Record'), True, (250, 0, 0)), (50, 46)) display.blit(font.render('GNSS:% 24s' % ('(% 3.8f, % 3.8f, % 3.8f)' % ( Gnss_sensor.lat, Gnss_sensor.lon, Gnss_sensor.alt)), True, (250, 0, 0)), (50, 100)) display.blit(font.render('x=%5.8f,y=%5.8f,z=%5.8f (m)' % ( Pose.location.x, Pose.location.y, Pose.location.z), True, (250, 0, 0)), (50, 118)) display.blit(font.render('vx=%5.8f,vy=%5.8f,vz=%5.8f (m/sec)' % ( velo.x, velo.y, velo.z), True, (250, 0, 0)), (50, 136)) display.blit(font.render('ax=%5.8f,ay=%5.8f,az=%5.8f (m/sec^2)' % ( Accl.x, Accl.y, Accl.z), True, (250, 0, 0)), (50, 154)) display.blit(font.render('roll=%5.8f,pitch=%5.8f,yaw=%5.8f (rad)' % ( math.radians(Pose.rotation.roll), math.radians(Pose.rotation.pitch), math.radians(Pose.rotation.yaw)), True, (250, 0, 0)), (50, 172)) display.blit(font.render('r_d=%5.8f,p_d=%5.8f,y_d=%5.8f (rad/sec)' % ( math.radians(AngV.x), math.radians(AngV.y), math.radians(AngV.z)), True, (250, 0, 0)), (50, 190)) pygame.display.flip() finally: print('destroying actors.') for actor in actor_list: actor.destroy() file_rgb.close() file_depth.close() file_groundtruth_sync.close() file_GNSS.close() file_veh_sim.close() file_associate.close() pygame.quit() print('done.') if __name__ == '__main__': try: main() except KeyboardInterrupt: print('\nCancelled by user. Bye!') ================================================ FILE: camera_calibration/undistort.py ================================================ import cv2 as cv import numpy as np import torch ImageSizeX = 1600 ImageSizeY = 900 CameraFOV = 150 f = ImageSizeX /(2 * np.tan(CameraFOV * np.pi / 360)) Cx = ImageSizeX / 2 Cy = ImageSizeY / 2 intrinsics = np.array([[f, 0, Cx], [0, f, Cy], [0, 0, 1 ]]) distortion_matrix = np.array([[ 0.00888296, -0.00130899, 0.00012061, -0.00338673, 0.00028834]]) newcameramtx, roi = cv.getOptimalNewCameraMatrix(intrinsics, distortion_matrix, (1600, 900), 1, (1600, 900)) # newcameramtx = np.array([[304.14395142, 0, 788.25758876,], # [ 0, 221.49429321, 449.78972161,], # [ 0, 0, 1, ],]) #print(roi, newcameramtx) original_img = cv.imread("test" + '.png') mapx, mapy = cv.initUndistortRectifyMap(intrinsics, distortion_matrix, None, newcameramtx, (ImageSizeX, ImageSizeY), 5) undistorted_img = cv.remap(original_img, mapx, mapy, cv.INTER_LINEAR) cv.imwrite("undistort.png", undistorted_img) ================================================ FILE: dataset/tools/generate_metadata.py ================================================ import json import pickle import os, sys towns = ["01", "02", "03", "04","05", "06", "07", "10"] index_per_down = ["val"] + [str(_).zfill(2) for _ in range(0, 11)] data_folder = "../" json_path = "../collect_data_json" ## Store the length of each route since we truncate those ones with infraction happening length_dict = {} for town_name in towns: for data_index in index_per_down: length_dict["town"+town_name+"_"+data_index] = {} try: with open(os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), "r") as f: records = json.load(f)["_checkpoint"]["records"] except: print("No json for", os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), flush=True) continue for index, record in enumerate(records): record = records[index] route_data_folder = os.path.join(data_folder, "town"+town_name+"_"+data_index, record["meta"]["folder_name"]) measurements_files = os.listdir(os.path.join(route_data_folder, "measurements")) total_length = len(measurements_files) if record["scores"]["score_composed"] >= 100: length_dict["town"+town_name+"_"+data_index][route_data_folder] = total_length continue # timeout or blocked, remove the last ones where the vehicle stops if len(record["infractions"]["route_timeout"]) > 0 or \ len(record["infractions"]["vehicle_blocked"]) > 0: stop_index = 0 for i in range(total_length-1, 0, -1): fname = os.path.join(route_data_folder, "measurements", str(i).zfill(4)) + ".json" with open(fname, 'r') as mf: speed = json.load(mf)["speed"] if speed > 0.1: stop_index = i break length_dict["town"+town_name+"_"+data_index][route_data_folder] = min(total_length, stop_index + 5) # collision or red-light elif len(record["infractions"]["red_light"]) > 0 or \ len(record["infractions"]["collisions_pedestrian"]) > 0 or \ len(record["infractions"]["collisions_vehicle"]) > 0 or \ len(record["infractions"]["collisions_layout"]) > 0: length_dict["town"+town_name+"_"+data_index][route_data_folder] = max(0, total_length-10) print(os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), "Routes with Jsons Finished", flush=True) #### Data without any json file all_town_folder = os.listdir(data_folder) for town_name in towns: for data_index in index_per_down: if "town"+town_name+"_"+data_index in all_town_folder: all_route_folder = os.listdir(os.path.join(data_folder, "town"+town_name+"_"+data_index)) for route_folder in all_route_folder: route_data_folder = os.path.join(data_folder, "town"+town_name+"_"+data_index, route_folder) if route_data_folder in length_dict["town"+town_name+"_"+data_index]: continue measurements_files = os.listdir(os.path.join(route_data_folder, "measurements")) total_length = len(measurements_files) if total_length > 10: total_length = total_length - 10 stop_index = 0 for i in range(total_length-1, 0, -1): fname = os.path.join(route_data_folder, "measurements", str(i).zfill(4)) + ".json" with open(fname, 'r') as mf: speed = json.load(mf)["speed"] if speed > 0.1: stop_index = i break length_dict["town"+town_name+"_"+data_index][route_data_folder] = min(total_length, stop_index + 5) print(os.path.join(json_path, "data_collect_town"+town_name+"_"+data_index+"_results.json", ), "Routes without Jsons Finished", flush=True) print("Town-Name #Route-Per-Town #Frames -------------------") total_cnt = 0 for town_name in length_dict: cnt = 0 for number_of_frames_per_route in length_dict[town_name].values(): cnt += number_of_frames_per_route print(town_name, length_dict[town_name], cnt) total_cnt += cnt print("Total Frames:", total_cnt) with open("../dataset_metadata.pkl", "wb") as f: pickle.dump(length_dict, f) print("Dataset metadata pickle saved") ================================================ FILE: dataset/tools/generate_random_routes.py ================================================ import glob import os import sys sys.path.append('../../') import lxml.etree as ET import argparse import random import time import carla from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO WEATHER_LIST = {'ClearNoon':{'cloudiness': 15.0, 'precipitation': 0.0, 'precipitation_deposits': 0.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 0.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'CloudyNoon':{'cloudiness': 80.0, 'precipitation': 0.0, 'precipitation_deposits': 0.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 45.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'WetNoon':{'cloudiness': 20.0, 'precipitation': 0.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 45.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'WetCloudyNoon':{'cloudiness': 90.0, 'precipitation': 0.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 180.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'SoftRainNoon':{'cloudiness': 90.0, 'precipitation': 15.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 315.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'MidRainyNoon':{'cloudiness': 80.0, 'precipitation': 30.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.40, 'sun_azimuth_angle': 0.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'HardRainNoon':{'cloudiness': 90.0, 'precipitation': 60.0, 'precipitation_deposits': 100.0, 'wind_intensity':1.0, 'sun_azimuth_angle': 90.0, 'sun_altitude_angle': 75.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'ClearSunset':{'cloudiness': 15.0, 'precipitation': 0.0, 'precipitation_deposits': 0.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 45.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'CloudySunset':{'cloudiness': 80.0, 'precipitation': 0.0, 'precipitation_deposits': 0.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 270.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'WetSunset':{'cloudiness': 20.0, 'precipitation': 0.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 270.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'WetCloudySunset':{'cloudiness': 90.0, 'precipitation': 0.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 0.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'MidRainSunset':{'cloudiness': 80.0, 'precipitation': 30.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.40, 'sun_azimuth_angle': 270.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'HardRainSunset':{'cloudiness': 80.0, 'precipitation': 60.0, 'precipitation_deposits': 100.0, 'wind_intensity':1.0, 'sun_azimuth_angle': 0.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'SoftRainSunset':{'cloudiness': 90.0, 'precipitation': 15.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.35, 'sun_azimuth_angle': 270.0, 'sun_altitude_angle': 15.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'ClearNight':{'cloudiness': 15.0, 'precipitation': 0.0, 'precipitation_deposits': 0.0, 'wind_intensity': 0.35, 'sun_azimuth_angle': 0.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'CloudyNight':{'cloudiness': 80.0, 'precipitation': 0.0, 'precipitation_deposits': 0.0, 'wind_intensity': 0.35, 'sun_azimuth_angle': 45.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'WetNight':{'cloudiness': 20.0, 'precipitation': 0.0, 'precipitation_deposits': 50.0, 'wind_intensity': 0.35, 'sun_azimuth_angle': 225.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'WetCloudyNight':{'cloudiness': 90.0, 'precipitation': 0.0, 'precipitation_deposits': 50.0, 'wind_intensity': 0.35, 'sun_azimuth_angle': 225.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'SoftRainNight':{'cloudiness': 90.0, 'precipitation': 15.0, 'precipitation_deposits': 50.0, 'wind_intensity': 0.35, 'sun_azimuth_angle': 270.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'MidRainyNight':{'cloudiness': 80.0, 'precipitation': 30.0, 'precipitation_deposits': 50.0, 'wind_intensity':0.4, 'sun_azimuth_angle': 225.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, 'HardRainNight':{'cloudiness': 90.0, 'precipitation': 60.0, 'precipitation_deposits': 100.0, 'wind_intensity':1, 'sun_azimuth_angle': 225.0, 'sun_altitude_angle': -80.0, 'fog_density': 0.0, 'fog_distance': 0.0, 'fog_falloff': 0.0, 'wetness': 0.0, }, } def interpolate_trajectory(world_map, waypoints_trajectory, hop_resolution=1.0): """ Given some raw keypoints interpolate a full dense trajectory to be used by the user. Args: world: an reference to the CARLA world so we can use the planner waypoints_trajectory: the current coarse trajectory hop_resolution: is the resolution, how dense is the provided trajectory going to be made Return: route: full interpolated route both in GPS coordinates and also in its original form. """ dao = GlobalRoutePlannerDAO(world_map, hop_resolution) grp = GlobalRoutePlanner(dao) grp.setup() # Obtain route plan route = [] is_junction = False distance = 0 try: for i in range(len(waypoints_trajectory) - 1): # Goes until the one before the last. waypoint = waypoints_trajectory[i] waypoint_next = waypoints_trajectory[i + 1] interpolated_trace = grp.trace_route(waypoint, waypoint_next) for i, wp_tuple in enumerate(interpolated_trace): route.append(wp_tuple[0].transform) if i > 0: distance += wp_tuple[0].transform.location.distance(interpolated_trace[i-1][0].transform.location) if not is_junction: is_junction = wp_tuple[0].is_junction # print (wp_tuple[0].transform.location, wp_tuple[1]) except: return None, distance, is_junction return route, distance, is_junction import subprocess def kill_carla(): kill_process = subprocess.Popen('killall -9 -r CarlaUE4-Linux', shell=True) kill_process.wait() time.sleep(5) def main(): carla_path = os.environ["CARLA_ROOT"] cmd = 'DISPLAY= bash ' + os.path.join(carla_path, 'CarlaUE4.sh')+f' -opengl -carla-rpc-port={args.port} -nosound' server_process = subprocess.Popen(cmd, shell=True, preexec_fn=os.setsid) time.sleep(10) ## Wait for carla client = carla.Client('localhost', int(args.port)) client.set_timeout(200.0) print("find carla!", args, flush=True) world = client.load_world(args.town) print ('loaded world') waypoint_list = world.get_map().generate_waypoints(2.0) print ('got %d possible waypoint'%len(waypoint_list)) actors = world.get_actors() traffic_lights_list = actors.filter('*traffic_light') print ('got %d traffic lights'%len(traffic_lights_list)) max_dist = 300 min_dist = 50 valid_route_list = [] number = 0 distance_list = [] is_junction_list = [] world_map = world.get_map() root = ET.Element('routes') while number < args.route_num: start_wp = random.choice(waypoint_list) end_wp = random.choice(waypoint_list) start_wp = world_map.get_waypoint(start_wp.transform.location,project_to_road=True, lane_type=carla.LaneType.Driving) end_wp = world_map.get_waypoint(end_wp.transform.location,project_to_road=True, lane_type=carla.LaneType.Driving) if start_wp.transform.location.distance(end_wp.transform.location) < min_dist or start_wp.transform.location.distance(end_wp.transform.location) > max_dist: continue wp_list, distance, is_junction = interpolate_trajectory(world_map, [start_wp.transform.location, end_wp.transform.location]) if wp_list is None: continue if distance <= min_dist or distance >= max_dist: continue distance_list.append(distance) is_junction_list.append(is_junction) route = ET.SubElement(root, 'route', id='%d'%number, town=args.town) # choose a random weather weather = random.choice(list(WEATHER_LIST.keys())) route = ET.SubElement(route, 'weather', id=weather, cloudiness='%f'%WEATHER_LIST[weather]['cloudiness'], precipitation='%f'%WEATHER_LIST[weather]['precipitation'], precipitation_deposits='%f'%WEATHER_LIST[weather]['precipitation_deposits'], wind_intensity='%f'%WEATHER_LIST[weather]['wind_intensity'], sun_azimuth_angle='%f'%WEATHER_LIST[weather]['sun_azimuth_angle'], sun_altitude_angle='%f'%WEATHER_LIST[weather]['sun_altitude_angle'], fog_density='%f'%WEATHER_LIST[weather]['fog_density'], fog_distance='%f'%WEATHER_LIST[weather]['fog_distance'], fog_falloff='%f'%WEATHER_LIST[weather]['fog_falloff'],wetness='%f'%WEATHER_LIST[weather]['wetness']) x, y, yaw = start_wp.transform.location.x, start_wp.transform.location.y, start_wp.transform.rotation.yaw ET.SubElement(route, 'waypoint', x='%f'%x, y='%f'%y, z='0.0', pitch='0.0', roll='0.0', yaw='%f'%yaw) x, y, yaw = end_wp.transform.location.x, end_wp.transform.location.y, end_wp.transform.rotation.yaw ET.SubElement(route, 'waypoint', x='%f'%x, y='%f'%y, z='0.0', pitch='0.0', roll='0.0', yaw='%f'%yaw) number += 1 print(number) print('Avg distance:', sum(distance_list)/number) print('Portion of going through junction:', sum(is_junction_list)/number) tree = ET.ElementTree(root) if args.save_file is not None: tree.write(args.save_file, xml_declaration=True, encoding='utf-8', pretty_print=True) if __name__ == '__main__': global args parser = argparse.ArgumentParser() parser.add_argument('--save_file', type=str, required=False, default="./", help='xml file path to save the route waypoints') parser.add_argument('--town', type=str, default='Town02', help='town for generating routes') parser.add_argument('--route_num', type=int, default=300, help='number of routes') parser.add_argument('--port', type=int, default=20023, help='number of routes') args = parser.parse_args() main() ================================================ FILE: docs/DATA_PREP.md ================================================ # Prepare Dataset ## Script to Collect for One Xml File Due to the huge size of the dataset (189K frames - 8TB, 2M frames - 85TB), we provide the instructations to generate the dataset. If the size is still too large for your device, techniques to reduce the size of files could be explored. We look forward to your contributions:). Update: If your disk space is limited, you could consider trying the techniques mentioned in the compression section of this awesome repo [carla_garge](https://github.com/autonomousvision/carla_garage/blob/main/docs/engineering.md). The command to collect data from one .xml file is: ```shell ## In the ThinkTwice/ directory port_for_carla=22023 ## Change the port for each running script to avoid cofliction port_for_traffic_manager=22033 ## Change the port for each running script to avoid cofliction route_file=town05_00 is_resume=False ## If there is the corresponding json file in the folder collect_data_json, you could set it as True to continue after the last finished route. is_local=True agent_name=roach_ap_agent_data_collection scenario_file=all_towns_traffic_scenarios_no256 cuda_device=0 CUDA_VISIBLE_DEVICES=$cuda_device nohup bash ./leaderboard/scripts/collect_data.sh $port_for_carla $port_for_traffic_manager $route_file $is_resume $is_local $agent_name $scenario_file 2>&1 > $route_file.log & ``` or simply: ```shell CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/collect_data.sh 22023 22033 town05_00 False True roach_ap_agent_data_collection all_towns_traffic_scenarios_no256 2>&1 > town05_00.log & ``` Note that one Carla simulator will be opened by the script and there is no need to open Carla manually. **You should manually kill that Carla to avoid *error: address is used* after the collection is done or reports errors.** ## Collect Whole Dataset For 189K training data + the rest of open loop valdiation data = 400k frames in TCP, please collect data with .xmls in [leaderboard/data/routes_for_open_loop_training](../leaderboard/data/routes_for_open_loop_training) with suffix *00, 01, 02, val*. During open-looped running, we train on town 01,03, 04, 06 and validate on town 02, 05 as in LAV, Transfuser, TCP. For 2M frames data, please collect data with all .xmls in [leaderboard/data/routes_for_open_loop_training](../leaderboard/data/routes_for_open_loop_training). During open-looped running, we train on all routes except those with suffix *val*. ## Generate More Routes If you want to collect more data with random routes, you could use [dataset/tools/generate_random_routes.py](../dataset/tools/generate_random_routes.py) ```shell CUDA_VISIBLE_DEVICES=0 python generate_random_routes.py --save_file tmp.xml --town Town02 --route_num 5 --port 22023 ``` ## Generate Metadata for Open-Loop Training After collecting data by the expert, we filter out those frames where expert made mistakes and then generate the meta information for all routes together: ```shell #In ThinkTwice/dataset/tools directory python generate_metadata.py #It could take a day for the 2M frames dataset. ``` ## Additional Notes - We strongly recommnd you **first collecting a small number of data** (for example, one route with ~20 frames) to make sure that the functions of open-loop training and closed-loop evaluation work well (by thorough visualizations and test runs). Otherwise, it could be time-consuming and frustrating to find out that there are some bugs or missing information (for example, we do not use semantic lidar sensor in our code). - Since we do not use any bounding boxs in our code, **if you would like to add some functions about bounding box, please first make sure that the collected information is correct and enough for your desired usage.** Test runs and visualizations as mentioned in the previous note is strongly recommended. - There are several coordinate system within the code: Unreal, Roach, Lidar, Camera, GNSS, Control, etc. If you want to modify or add any new component, visualizations to check whether they align with existing ones are strongly recommended - You could modify [leaderboard/team_code/roach_ap_agent_data_collection.py](../leaderboard/team_code/roach_ap_agent_data_collection.py) to save the information you need for training. - For the size of images, we collect images at 900x1600 and we downsample them into 448x896 to save GPU memory. Thus, you may change the collected images' resolution (as well as depth and segmentation labels) to save disk space. - For traffic light segmentation in images, we wrote rules regarding color to generate GT, which might not be accurate. You could consider use the build-in API of Carla to generate the GT. - To reduce the data collection cost, you could first only collect data from Town01, Town03, Town04, and Town06 for training as in Appendix B Table 1 of [TCP](https://arxiv.org/pdf/2206.08129.pdf) and do not conduct open-loop validation, which could approximately half the needed data. When the model achieves *current_throttle_brake_offset < 0.1* and *longitudinal_offset < 0.2* in training set, it is considered fitting well. ================================================ FILE: docs/EVAL.md ================================================ # Clsoed-Loop Evaluation To evaluate in the town05long: ```shell ## In the ThinkTwice/ directory port_for_carla=22023 ## Change the port for each running script to avoid cofliction port_for_traffic_manager=22033 ## Change the port for each running script to avoid cofliction team_agent=thinktwice_agent is_resume=False ## If there is the corresponding json file in the folder closed_loop_eval_log, you could set it as True to continue after the last finished route. is_local=True ckpt_and_config_path=open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py scenario_file=all_towns_traffic_scenarios_no256 cuda_device=0 setting_name=thinktwice_town05long CUDA_VISIBLE_DEVICES=$cuda_device nohup bash ./leaderboard/scripts/evaluation_town05long.sh $port_for_carla $port_for_traffic_manager $team_agent $is_resume $is_local $ckpt_and_config_path $scenario_file $setting_name 2>&1 > $setting_name.log & ``` or simply: ```shell ## In the ThinkTwice/ directory CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/evaluation_town05long.sh 22023 22033 thinktwice_agent False True open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py all_towns_traffic_scenarios_no256 thinktwice_town05long 2>&1 > thinktwice_town05long.log & ``` To evaluate in the longest6, you can simply use: ```shell ## In the ThinkTwice/ directory CUDA_VISIBLE_DEVICES=0 nohup bash ./leaderboard/scripts/evaluation_longest6.sh 23023 23033 thinktwice_agent False True open_loop_training/ckpt/thinktwice.pth+open_loop_training/configs/thinktwice.py longest6_eval_scenarios thinktwice_longest6 2>&1 > thinktwice_longest6.log & ``` Note that the evaluation result is in the directory **closed_loop_eval_log/results_$setting_name.json** and the visualizations and recordings for debug (top-down view, front view, and canbus) are in the directory **closed_loop_eval_log/eval_log/$setting_name**. Warning: The visualizations and recordings could take lots of disk space. Please monitor those folders in the [closed_loop_eval_log/eval_log/](../closed_loop_eval_log/eval_log/) and delete those useless ones in time. You could also modify the **save** function of [leaderboard/team_code/thinktwice_agent.py](../leaderboard/team_code/thinktwice_agent.py) to change the saved information during evaluation. Update: As kindly reminded by the authors of [carla_garge](https://github.com/autonomousvision/carla_garage) (One awsome repo for e2e ad! Check it out for more detials), we update the implementation of longest6 to align with the one used by [Transfuser](https://github.com/autonomousvision/transfuser/tree/2022/leaderboard). Specifically, they ignore the penalty score of running stop sign and increase the number of agents in the scene. ================================================ FILE: docs/INSTALL.md ================================================ # Installation Modified from mmdetection3d, BEVFormer, UniAD **a. Env: Create a conda virtual environment and activate it.** ```shell conda create -n thinktwice python=3.7 -y ## Must be py3.7 required by Carla 9.10 conda activate thinktwice ``` **b. Torch: Install PyTorch and torchvision following the [official instructions](https://pytorch.org/).** ```shell conda install pytorch==1.12.1 torchvision==0.13.1 torchaudio==0.12.1 cudatoolkit=11.3 -c pytorch -y ``` **c. GCC: Make sure gcc>=5 in conda env.** ```shell conda install -c omgarcia gcc-6 conda install libgcc -y conda install -c conda-forge libcxxabi -y ``` **d. CUDA: Before installing MMCV family, you need to set up the environment variables in ~/.bashrc (for compiling some operators on the gpu).** ```shell export CUDA_HOME=YOUR_CUDA_PATH/ # Eg: export CUDA_HOME=/mnt/cuda-11.3/ export PATH=$PATH:YOUR_CUDA_PATH//bin # Eg: export CUDA_HOME=/mnt/cuda-11.3/bin export LD_LIBRARY_PATH=YOUR_CUDA_PATH/lib64:YOUR_CONDA_PATH/envs/thinktwice/lib # Eg: export LD_LIBRARY_PATH=/mnt/cuda-11.3/lib64:/mnt/miniconda3/envs/thinktwice/lib export LD_PRELOAD=YOUR_CONDA_PATH/envs/thinktwice/lib/libstdc++.so.6.0.29 # Eg: export LD_PRELOAD=/mnt/miniconda3/envs/thinktwice/lib/libstdc++.so.6.0.29 ``` **e. Install mmcv-full, mmdet, and mmseg** ```shell pip install mmcv-full==1.7.0 -f https://download.openmmlab.com/mmcv/dist/cu113/torch1.12/index.html pip install mmdet==2.28.2 pip install mmsegmentation==0.30.0 ``` **f. Install mmdet3d from source code.** ```shell git clone https://github.com/open-mmlab/mmdetection3d.git -b 1.0 ## Note that 1.1 is incompatible cd mmdetection3d pip install cumm-cu113 pip install spconv-cu113 ## For fast lidar model MMCV_WITH_OPS=1 FORCE_CUDA=1 pip install -v -e . ## Must have a GPU ``` **g. Other Requirements.** ```shell conda install -c anaconda protobuf -y conda install matplotlib -y conda install requests -y conda install tabulate -y conda install protobuf -y conda install -c anaconda setuptools -y conda install -c conda-forge libjpeg-turbo -y conda install -c anaconda decorator -y conda install shapely -y conda install -c anaconda ephem -y conda install -c conda-forge omegaconf -y conda install -c conda-forge hydra -y conda install -c anaconda scikit-image -y conda install -c conda-forge opt_einsum -y conda install -c conda-forge mpi4py -y conda install h5py -y conda install -c conda-forge importlib-metadata -y conda install -c conda-forge zipp -y pip install gym==0.17.2 pip install imgaug pip install opencv-python pip install opencv-contrib-python pip install pygame pip install py_trees==0.8.1 pip install dictor pip install gym==0.17.2 pip install stable-baselines3==0.8.0 pip install numpy --upgrade pip install shapely==1.6.4.post2 --force-reinstall ### Important! Higher version of shapely may make the CARLA crash mysteriously! ``` **h. Install Carla. (From Roach)** ```shell mkdir carla cd carla wget https://carla-releases.s3.eu-west-3.amazonaws.com/Linux/CARLA_0.9.10.1.tar.gz tar -xvzf CARLA_0.9.10.1.tar.gz echo "export CARLA_ROOT=/mnt/carla" >> /mnt/.bashrc ## Set to your own Carla path and ~/.bashrc in your system cd Import && wget https://carla-releases.s3.eu-west-3.amazonaws.com/Linux/AdditionalMaps_0.9.10.1.tar.gz cd .. && bash ImportAssets.sh rm CARLA_0.9.11.tar.gz Import/AdditionalMaps_0.9.10.1.tar.gz rm Import/AdditionalMaps_0.9.10.1.tar.gz Import/AdditionalMaps_0.9.11.tar.gz cd && source .bashrc echo "$CARLA_ROOT/PythonAPI/carla/dist/carla-0.9.10-py3.7-linux-x86_64.egg" >> YOUR_CONDA_PATH/envs/thinktwice/lib/python3.7/site-packages/carla.pth ``` **i. Clone ThinkTwice.** ```shell git clone git@github.com:OpenDriveLab/ThinkTwice.git cd ThinkTwice/open_loop_training python setup.py develop ## Compile CUDA function for LSS from BEVDepth ``` ================================================ FILE: docs/TRAIN.md ================================================ # Train Your Model ## Script For Training Our training pipeline is based on [mmcv](https://github.com/open-mmlab/mmcv) and [mmdet3d](https://github.com/open-mmlab/mmdetection3d). To train a ThinkTwice model, you could use: ```shell #In ThinkTwice/open_loop_training/ directory #We train on 16 A100 for 4 days CUDA_VISIBLE_DEVICES=0,1,2,3,4,5,6,7, python -m torch.distributed.launch --nproc_per_node=8 --master_port=22023 train.py configs/thinktwice.py --work-dir=work_dirs/thinktwice --launcher="pytorch" ``` For single GPU debug, you could simply use: ```shell #In ThinkTwice/open_loop_training/ directory CUDA_VISIBLE_DEVICES=0 python train.py configs/thinktwice.py --work-dir=work_dirs/debug ``` ## Code Structure We give the structure of the training code. Note that We only introduce those folders/files are commonly used and modified. ThinkTwice/open_loop_training ├── ckpt # Checkpoints ├── configs # Hyper-Parameter ├── work_dirs # Training Log ├── code # Preprocessing, DataLoader, Model │ ├── apis # Training pipeline for mmdet3D │ ├── core # The hooks for mmdet3D │ ├── datasets # Preprocessing and DataLoader | | ├── pipelines # Functions of Preprocessing and DataLoader │ | ├── samplers # For DDP │ | └── carla_dataset.py # Framework of Preprocessing and DataLoading │ ├── model_code # Neural Network | | ├── backbones # Module of Encoder | | └── dense_heads # Module of Decoder and Loss Functions │ └── encoder_decoder_framework.py # Entrance of Neural Network └── train.py # Entrance of Training ## Tips - Change **is_dev** in [open_loop_training/configs/thinktwice.py](../open_loop_training/configs/thinktwice.py) to True when you develop your model and to False during training - Set **is_full** in [open_loop_training/configs/thinktwice.py](../open_loop_training/configs/thinktwice.py) to False would only use the same number of data as TCP while to True would use all possible data recorded in **dataset/dataset_metadata.pkl**. - Your could start with [open_loop_training/code/encoder_decoder_framework.py](../open_loop_training/configs/thinktwice.py) when you want to learn about the neural network and [open_loop_training/code/datasets/carla_dataset.py](../open_loop_training/configs/thinktwice.py) when you want to learn about data. ================================================ FILE: leaderboard/LICENSE ================================================ MIT License Copyright (c) 2019 CARLA 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. ================================================ FILE: leaderboard/README.md ================================================ ## Note by ThinkTwice We have changed/added some log related functions of the leaderboard for easier debug. For example, each simulated route would have a index in its folder name. For all infractions, the location and timestep would be recorded in the json file. ## Original README.md The main goal of the CARLA Autonomous Driving Leaderboard is to evaluate the driving proficiency of autonomous agents in realistic traffic situations. The leaderboard serves as an open platform for the community to perform fair and reproducible evaluations, simplifying the comparison between different approaches. Autonomous agents have to drive through a set of predefined routes. For each route, agents are initialized at a starting point and have to drive to a destination point. The agents will be provided with a description of the route. Routes will happen in a variety of areas, including freeways, urban scenes, and residential districts. Agents will face multiple traffic situations based in the NHTSA typology, such as: * Lane merging * Lane changing * Negotiations at traffic intersections * Negotiations at roundabouts * Handling traffic lights and traffic signs * Coping with pedestrians, cyclists and other elements The user can change the weather of the simulation, allowing the evaluation of the agent in a variety of weather conditions, including daylight scenes, sunset, rain, fog, and night, among others. More information can be found [here](https://leaderboard.carla.org/) ================================================ FILE: leaderboard/data/routes_for_evaluation/routes_longest6.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_evaluation/routes_town05_long.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town01_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town02_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town03_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town04_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town05_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town06_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town07_val.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_00.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_01.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_02.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_03.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_04.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_05.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_06.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_07.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_08.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_09.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_10.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_11.xml ================================================ ================================================ FILE: leaderboard/data/routes_for_open_loop_training/routes_town10_val.xml ================================================ ================================================ FILE: leaderboard/data/scenarios/all_towns_traffic_scenarios_no256.json ================================================ { "available_scenarios": [ { "Town01": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "167.69", "y": "1.93", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "165.10", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "373.9", "y": "-2.4", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.53", "y": "37.27", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "234.28", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "199.78", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "168.51", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "134.1", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "94.27", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "59.77", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.24", "y": "-1.87", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "158.80", "y": "36.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.17", "y": "-1.91", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "92.99", "y": "35.91", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "87.99", "y": "20.43", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.87", "y": "55.22", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.47", "y": "94.86", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.56", "y": "129.21", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.35", "y": "160.10", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "127.21", "y": "195.29", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.28", "y": "59.38", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "153.78", "y": "20.38", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "53.0", "y": "330.25", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.86", "y": "292.27", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "300.57", "y": "331.2", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "334.60", "y": "291.92", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.25", "y": "160.22", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "338.75", "y": "234.22", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.25", "y": "160.22", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "338.75", "y": "234.22", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "373.9", "y": "-2.4", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.53", "y": "37.27", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "234.28", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "199.78", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "168.51", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "134.1", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "94.27", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "59.77", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.24", "y": "-1.87", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "158.80", "y": "36.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.17", "y": "-1.91", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "92.99", "y": "35.91", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "87.99", "y": "20.43", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.87", "y": "55.22", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.47", "y": "94.86", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.56", "y": "129.21", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.35", "y": "160.10", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "127.21", "y": "195.29", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.28", "y": "59.38", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "153.78", "y": "20.38", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "53.0", "y": "330.25", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.86", "y": "292.27", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "300.57", "y": "331.2", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "334.60", "y": "291.92", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [], "scenario_type": "Scenario10" } ], "Town02": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.28", "y": "161.41", "yaw": "90.0", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "23.72", "y": "187.41", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.28", "y": "161.41", "yaw": "90.0", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "23.72", "y": "187.41", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [], "scenario_type": "Scenario10" } ], "Town03": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -44.77, "y": 197.2, "yaw": 187.0, "z": 1.74 } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0.0", "x": "-73.64797973632812", "y": "165.80230712890625", "yaw": "257.414306640625", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -77.8, "y": 34.5, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.094234466552734", "y": "69.08776092529297", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 244.44, "y": 44.28, "yaw": 271.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "241.04603576660156", "y": "44.19745635986328", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 46.52, "y": -196.33, "yaw": 1.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "46.43220520019531", "y": "-192.8362274169922", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.6, "y": -163.36, "yaw": 91.0, "z": 1.82 } }, { "transform": { "pitch": "360.0", "x": "-3.4487547874450684", "y": "-163.4599151611328", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } }, { "transform": { "pitch": "360.0", "x": "244.55511474609375", "y": "43.866703033447266", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -37.73, "y": 0.99, "yaw": 7.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 32.76, "y": -8.17, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.66706466674805", "y": "-4.5203680992126465", "yaw": "181.4586181640625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.45, "y": -4.56, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.539730072021484", "y": "-8.024791717529297", "yaw": "181.48350524902344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": {}, "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "28.78", "y": "196.68", "yaw": "180.072144", "z": "0.99" }, { "pitch": "0.0", "x": "27.30", "y": "193.64", "yaw": "180.072144", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "11.706635", "x": "150.69", "y": "-164.90", "yaw": "91.510803", "z": "5.2" } ], "right": [ { "pitch": "358.462036", "x": "153.26", "y": "-100.40", "yaw": "271.510834", "z": "9.82" } ] }, "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.55", "y": "98.97", "yaw": "270.182343", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.18", "y": "33.11", "yaw": "90.185455", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-120.9", "y": "41.36", "yaw": "134.365295", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -149.58, "y": 40.72, "yaw": 90.0, "z": 0.99 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-120.27", "y": "40.79", "yaw": "133.405731", "z": "0.99" }, { "pitch": "0.0", "x": "-110.74", "y": "25.41", "yaw": "133.243774", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.9", "y": "100.67", "yaw": "267.650696", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.8", "y": "33.43", "yaw": "89.421509", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "109.25", "y": "-6.99", "yaw": "181.86908", "z": "1.54" } ] }, "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "182.92", "y": "-6.10", "yaw": "181.491562", "z": "1.38" } ] }, "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "11.706635", "x": "150.69", "y": "-164.90", "yaw": "91.510803", "z": "5.2" } ], "right": [ { "pitch": "358.462036", "x": "153.26", "y": "-100.40", "yaw": "271.510834", "z": "9.82" } ] }, "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.55", "y": "98.97", "yaw": "270.182343", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.18", "y": "33.11", "yaw": "90.185455", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-120.9", "y": "41.36", "yaw": "134.365295", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -149.58, "y": 40.72, "yaw": 90.0, "z": 0.99 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-120.27", "y": "40.79", "yaw": "133.405731", "z": "0.99" }, { "pitch": "0.0", "x": "-110.74", "y": "25.41", "yaw": "133.243774", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.9", "y": "100.67", "yaw": "267.650696", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.8", "y": "33.43", "yaw": "89.421509", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "109.25", "y": "-6.99", "yaw": "181.86908", "z": "1.54" } ] }, "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "182.92", "y": "-6.10", "yaw": "181.491562", "z": "1.38" } ] }, "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "28.78", "y": "196.68", "yaw": "180.072144", "z": "0.99" }, { "pitch": "0.0", "x": "27.30", "y": "193.64", "yaw": "180.072144", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario10" } ], "Town04": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -333.24, "y": 435.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-332.98760986328125", "y": "432.04986572265625", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7461853027344", "y": "428.5581970214844", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.5047607421875", "y": "425.0665283203125", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 406.92, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.44630432128906", "y": "403.47784423828125", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.88621520996094", "y": "410.4554138183594", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.60617065429688", "y": "413.9441833496094", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -183.17, "y": 403.29, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-182.87094116210938", "y": "406.9427185058594", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.58535766601562", "y": "410.4310302734375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.29977416992188", "y": "413.91937255859375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -510.3, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-513.669189453125", "y": "92.98770141601562", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6730651855469", "y": "93.22088623046875", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17498779296875", "y": "93.33748626708984", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -514.1, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1750793457031", "y": "93.2253189086914", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6768493652344", "y": "93.33702087402344", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17864990234375", "y": "93.44872283935547", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -13.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-16.640460968017578", "y": "-230.1665802001953", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.651756286621094", "y": "-229.7690887451172", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.15740442276001", "y": "-229.57032775878906", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -487.27, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-483.66375732421875", "y": "245.8326873779297", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6600646972656", "y": "246.06027221679688", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1582336425781", "y": "246.17405700683594", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -483.59, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.15789794921875", "y": "246.0686798095703", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6559753417969", "y": "246.1850128173828", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1540222167969", "y": "246.30136108398438", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -9.69, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.133902549743652", "y": "-230.1801300048828", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.628005981445312", "y": "-230.38319396972656", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.145692825317383", "y": "-229.77401733398438", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 13.24, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "16.350406646728516", "y": "229.65643310546875", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.356184005737305", "y": "229.37210083007812", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.859072208404541", "y": "229.2299346923828", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.3, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624905586242676", "y": "-79.91557312011719", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.124932289123535", "y": "-79.90184020996094", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624959468841553", "y": "-79.88809967041016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.9, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": 16.8, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.859013557434082", "y": "229.3724365234375", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.361806869506836", "y": "229.2326202392578", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.864601135253906", "y": "229.09280395507812", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 432.39, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4604797363281", "y": "435.5253601074219", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.9693603515625", "y": "428.5426025390625", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7237854003906", "y": "425.0512390136719", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 36.18, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3785705566406", "x": "173.44720458984375", "y": "39.27357482910156", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.56666564941406", "y": "32.274593353271484", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.62640380859375", "y": "28.775104522705078", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 34.38, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2730407714844", "x": "6.096894264221191", "y": "37.6077880859375", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.125317096710205", "y": "30.607847213745117", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.139528274536133", "y": "27.10787582397461", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 34.29, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6138916015625", "y": "37.20619201660156", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60450744628906", "y": "30.206199645996094", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.59982299804688", "y": "26.70620346069336", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 33.53, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.24749755859375", "y": "37.024845123291016", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.2925109863281", "y": "30.02499008178711", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.31500244140625", "y": "26.525062561035156", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 39.53, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.37725830078125", "x": "173.5640869140625", "y": "35.775062561035156", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.6238250732422", "y": "32.275569915771484", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.68356323242188", "y": "28.776081085205078", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 37.73, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2725524902344", "x": "6.124706745147705", "y": "34.107872009277344", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.138918399810791", "y": "30.60790252685547", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.153129577636719", "y": "27.10793113708496", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 37.64, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60472106933594", "y": "33.70620346069336", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6000213623047", "y": "30.206205368041992", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.5953369140625", "y": "26.706209182739258", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 36.88, "yaw": 359.0, "z": 1.13 } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.2915344238281", "y": "33.52505874633789", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3140563964844", "y": "30.025129318237305", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3365478515625", "y": "26.52520179748535", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "0", "x": -12.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.358753204345703", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358806610107422", "y": "-75.72421264648438", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.8588337898254395", "y": "-75.73794555664062", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 14.1, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.49053955078125", "y": "10.631532669067383", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.69122314453125", "y": "17.62865447998047", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.79156494140625", "y": "21.127216339111328", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 11.9, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.3455047607422", "y": "7.477066993713379", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.2260284423828", "y": "14.47604751586914", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.16629028320312", "y": "17.97553825378418", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 9.52, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618186950683594", "y": "16.46259880065918", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 9.11, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41539001464844", "y": "5.670230388641357", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42477416992188", "y": "12.6702241897583", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42945861816406", "y": "16.17022132873535", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 10.45, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.70556640625", "y": "14.126648902893066", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.8155212402344", "y": "17.624921798706055", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.92547607421875", "y": "21.123193740844727", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 7.53, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.215087652206421", "x": "156.21119689941406", "y": "10.975284576416016", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.15145874023438", "y": "14.474775314331055", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.0917205810547", "y": "17.974266052246094", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 5.96, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.604219436645508", "y": "9.462596893310547", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618431091308594", "y": "12.962567329406738", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.63264274597168", "y": "16.462539672851562", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 5.55, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4248504638672", "y": "9.170221328735352", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42955017089844", "y": "12.670218467712402", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.43423461914062", "y": "16.170215606689453", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "0", "x": 385.91, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "382.6264343261719", "y": "-235.0435333251953", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "389.6253967285156", "y": "-235.16390991210938", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1248779296875", "y": "-235.22410583496094", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 409.22, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "412.61456298828125", "y": "-85.36454010009766", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61492919921875", "y": "-85.43766784667969", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1151123046875", "y": "-85.47423553466797", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-15.692474365234375", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.6925630569458", "y": "77.76168823242188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192607879638672", "y": "77.74402618408203", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 412.59, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1151123046875", "y": "-85.43630981445312", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61529541015625", "y": "-85.47286987304688", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.115478515625", "y": "-85.50943756103516", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.97, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.157381057739258", "y": "-229.76759338378906", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.662800788879395", "y": "-229.57290649414062", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.168219089508057", "y": "-229.3782196044922", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.59, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858835220336914", "y": "-75.72463989257812", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358861923217773", "y": "-75.7383804321289", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858889102935791", "y": "-75.75211334228516", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.94, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192610740661621", "y": "77.7610855102539", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.692655563354492", "y": "77.74342346191406", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192700386047363", "y": "77.72576141357422", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 11.74, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.124823570251465", "y": "-79.94327545166016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.1248779296875", "y": "-79.91580963134766", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624904632568359", "y": "-79.90206909179688", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 12.33, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.799628257751465", "y": "76.15249633789062", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.79971694946289", "y": "76.18782043457031", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.299761772155762", "y": "76.20548248291016", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 405.54, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1143493652344", "y": "-85.36266326904297", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6141662597656", "y": "-85.32609558105469", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1147155761719", "y": "-85.435791015625", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.31, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858723640441895", "y": "-75.6960678100586", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.35869598388672", "y": "-75.68233489990234", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858777046203613", "y": "-75.72354125976562", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -8.66, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192425727844238", "y": "77.79782104492188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692380905151367", "y": "77.81548309326172", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192514896392822", "y": "77.76249694824219", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.4, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624799728393555", "y": "-79.9426498413086", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124772071838379", "y": "-79.95638275146484", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624853134155273", "y": "-79.91517639160156", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.63, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "12.299577713012695", "y": "76.15148162841797", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79953384399414", "y": "76.13381958007812", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.2996673583984375", "y": "76.18680572509766", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.53, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.847021102905273", "y": "229.667236328125", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.34402847290039", "y": "229.8119354248047", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.853006362915039", "y": "229.37783813476562", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 428.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4712219238281", "y": "432.01580810546875", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.721435546875", "y": "435.5068664550781", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.97076416015625", "y": "425.0337219238281", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 410.82, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.47103881835938", "y": "406.9908752441406", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.74537658691406", "y": "403.50164794921875", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.92237854003906", "y": "413.9693298339844", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -506.72, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1669006347656", "y": "92.98015594482422", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.664794921875", "y": "92.85853576660156", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.1711120605469", "y": "93.223388671875", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -490.77, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.16552734375", "y": "245.8351593017578", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.66729736328125", "y": "245.72369384765625", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1619567871094", "y": "246.05809020996094", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 32.58, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3799743652344", "x": "173.4454803466797", "y": "35.77303695678711", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.38575744628906", "y": "39.272525787353516", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.56495666503906", "y": "28.774057388305664", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 30.78, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2735595703125", "x": "6.096487998962402", "y": "34.107757568359375", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.082276821136475", "y": "37.60772705078125", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.124910831451416", "y": "27.10781478881836", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 30.69, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61404418945312", "y": "33.7061882019043", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6187286376953", "y": "37.20618438720703", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6046600341797", "y": "26.706195831298828", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 29.93, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2468566894531", "y": "33.5247688293457", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.224365234375", "y": "37.024696350097656", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2918701171875", "y": "26.524913787841797", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 17.41, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.5028991699219", "y": "14.132526397705078", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.4099426269531", "y": "10.633761405944824", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.6888732910156", "y": "21.130056381225586", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 14.49, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3299560546875", "y": "10.977312088012695", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3896942138672", "y": "7.477822303771973", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.21047973632812", "y": "17.976293563842773", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 12.92, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575960159301758", "y": "9.462711334228516", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.561748504638672", "y": "5.962739944458008", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.60438346862793", "y": "16.46265411376953", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 12.51, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41551208496094", "y": "9.170232772827148", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41082763671875", "y": "5.670236110687256", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42489624023438", "y": "16.17022705078125", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "0", "x": 389.55, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "386.126953125", "y": "-235.0426788330078", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.62744140625", "y": "-234.98406982421875", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1259765625", "y": "-235.15989685058594", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 402.0, "y": -85.4, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "405.6141662597656", "y": "-85.36223602294922", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "409.1139831542969", "y": "-85.32567596435547", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6138000488281", "y": "-85.28910827636719", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 16.5, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575634002685547", "y": "12.962740898132324", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.56142234802246", "y": "9.462770462036133", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.547210693359375", "y": "5.962799072265625", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 16.9, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41432189941406", "y": "12.67023754119873", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4096221923828", "y": "9.17024040222168", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.40493774414062", "y": "5.670243740081787", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "0", "x": -6.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-9.628252983093262", "y": "-230.17373657226562", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-13.12211799621582", "y": "-230.38087463378906", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.615983963012695", "y": "-230.5880126953125", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-9.358698844909668", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.858672142028809", "y": "-75.68299865722656", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.358644485473633", "y": "-75.66926574707031", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-8.692384719848633", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.192340850830078", "y": "77.8146743774414", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692296028137207", "y": "77.83233642578125", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 4.69, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.12476921081543", "y": "-79.9434814453125", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "11.62474250793457", "y": "-79.95721435546875", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124715805053711", "y": "-79.970947265625", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.29, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.799537658691406", "y": "76.15229034423828", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "12.299492835998535", "y": "76.13462829589844", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79944896697998", "y": "76.1169662475586", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.19, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "9.344169616699219", "y": "229.6626434326172", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.841078758239746", "y": "229.80970764160156", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.337987899780273", "y": "229.95677185058594", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -494.19, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-490.6671142578125", "y": "245.83995056152344", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-487.1688232421875", "y": "245.7306671142578", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.6705322265625", "y": "245.6213836669922", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -503.22, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-506.6645202636719", "y": "92.97496795654297", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-510.1622009277344", "y": "92.84800720214844", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.659912109375", "y": "92.7210464477539", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 393.1, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "389.62744140625", "y": "-235.04331970214844", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "386.1278991699219", "y": "-234.98617553710938", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.6283874511719", "y": "-234.9290313720703", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 425.47, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.46160888671875", "y": "428.5073547363281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.71630859375", "y": "431.9980773925781", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.97100830078125", "y": "435.4888000488281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 414.14, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.45127868652344", "y": "410.49993896484375", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.72093200683594", "y": "407.0103454589844", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.99057006835938", "y": "403.520751953125", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.6, "y": 21.0, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.5164794921875", "y": "17.633331298828125", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.4296569824219", "y": "14.134408950805664", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.3428039550781", "y": "10.635486602783203", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 29.2, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3813171386719", "x": "173.4475555419922", "y": "32.272560119628906", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.3878173828125", "y": "35.77205276489258", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.32809448242188", "y": "39.271541595458984", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "2", "x": 326.5, "y": 20.8, "yaw": 180.0, "z": 1.7 } }, { "transform": { "pitch": "1.490559458732605", "x": "326.55828857421875", "y": "17.38355827331543", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6180114746094", "y": "13.88406753540039", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6777648925781", "y": "10.384577751159668", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 27.4, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2740478515625", "x": "6.096976280212402", "y": "30.607730865478516", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.082764625549316", "y": "34.10770034790039", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.068553447723389", "y": "37.60767364501953", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 27.31, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61387634277344", "y": "30.206186294555664", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6185760498047", "y": "33.70618438720703", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.62326049804688", "y": "37.206180572509766", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 26.55, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.24761962890625", "y": "30.024702072143555", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.22509765625", "y": "33.52463150024414", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.2026062011719", "y": "37.024559020996094", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 18.7, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.34207153320312", "y": "14.47802734375", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4018096923828", "y": "10.978536605834961", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4615478515625", "y": "7.479046821594238", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": -333.24, "y": 435.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-332.98760986328125", "y": "432.04986572265625", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7461853027344", "y": "428.5581970214844", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.5047607421875", "y": "425.0665283203125", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 406.92, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.44630432128906", "y": "403.47784423828125", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.88621520996094", "y": "410.4554138183594", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.60617065429688", "y": "413.9441833496094", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 403.29, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-182.87094116210938", "y": "406.9427185058594", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.58535766601562", "y": "410.4310302734375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.29977416992188", "y": "413.91937255859375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -510.3, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-513.669189453125", "y": "92.98770141601562", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6730651855469", "y": "93.22088623046875", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17498779296875", "y": "93.33748626708984", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -514.1, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1750793457031", "y": "93.2253189086914", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6768493652344", "y": "93.33702087402344", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17864990234375", "y": "93.44872283935547", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -13.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-16.640460968017578", "y": "-230.1665802001953", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.651756286621094", "y": "-229.7690887451172", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.15740442276001", "y": "-229.57032775878906", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -487.27, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-483.66375732421875", "y": "245.8326873779297", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6600646972656", "y": "246.06027221679688", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1582336425781", "y": "246.17405700683594", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -483.59, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.15789794921875", "y": "246.0686798095703", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6559753417969", "y": "246.1850128173828", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1540222167969", "y": "246.30136108398438", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.69, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.133902549743652", "y": "-230.1801300048828", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.628005981445312", "y": "-230.38319396972656", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.145692825317383", "y": "-229.77401733398438", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 13.24, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "16.350406646728516", "y": "229.65643310546875", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.356184005737305", "y": "229.37210083007812", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.859072208404541", "y": "229.2299346923828", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.3, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624905586242676", "y": "-79.91557312011719", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.124932289123535", "y": "-79.90184020996094", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624959468841553", "y": "-79.88809967041016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.9, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": 16.8, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.859013557434082", "y": "229.3724365234375", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.361806869506836", "y": "229.2326202392578", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.864601135253906", "y": "229.09280395507812", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 432.39, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4604797363281", "y": "435.5253601074219", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.9693603515625", "y": "428.5426025390625", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7237854003906", "y": "425.0512390136719", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 36.18, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3785705566406", "x": "173.44720458984375", "y": "39.27357482910156", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.56666564941406", "y": "32.274593353271484", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.62640380859375", "y": "28.775104522705078", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 34.38, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2730407714844", "x": "6.096894264221191", "y": "37.6077880859375", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.125317096710205", "y": "30.607847213745117", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.139528274536133", "y": "27.10787582397461", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 34.29, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6138916015625", "y": "37.20619201660156", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60450744628906", "y": "30.206199645996094", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.59982299804688", "y": "26.70620346069336", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 33.53, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.24749755859375", "y": "37.024845123291016", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.2925109863281", "y": "30.02499008178711", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.31500244140625", "y": "26.525062561035156", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 39.53, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.37725830078125", "x": "173.5640869140625", "y": "35.775062561035156", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.6238250732422", "y": "32.275569915771484", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.68356323242188", "y": "28.776081085205078", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 37.73, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2725524902344", "x": "6.124706745147705", "y": "34.107872009277344", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.138918399810791", "y": "30.60790252685547", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.153129577636719", "y": "27.10793113708496", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 37.64, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60472106933594", "y": "33.70620346069336", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6000213623047", "y": "30.206205368041992", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.5953369140625", "y": "26.706209182739258", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 36.88, "yaw": 359.0, "z": 1.13 } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.2915344238281", "y": "33.52505874633789", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3140563964844", "y": "30.025129318237305", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3365478515625", "y": "26.52520179748535", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "0", "x": -12.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.358753204345703", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358806610107422", "y": "-75.72421264648438", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.8588337898254395", "y": "-75.73794555664062", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 14.1, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.49053955078125", "y": "10.631532669067383", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.69122314453125", "y": "17.62865447998047", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.79156494140625", "y": "21.127216339111328", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 11.9, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.3455047607422", "y": "7.477066993713379", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.2260284423828", "y": "14.47604751586914", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.16629028320312", "y": "17.97553825378418", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 9.52, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.603975296020508", "y": "12.962626457214355", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618186950683594", "y": "16.46259880065918", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 9.11, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41539001464844", "y": "5.670230388641357", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42477416992188", "y": "12.6702241897583", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42945861816406", "y": "16.17022132873535", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 10.45, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.70556640625", "y": "14.126648902893066", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.8155212402344", "y": "17.624921798706055", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.92547607421875", "y": "21.123193740844727", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 7.53, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.215087652206421", "x": "156.21119689941406", "y": "10.975284576416016", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.15145874023438", "y": "14.474775314331055", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.0917205810547", "y": "17.974266052246094", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 5.96, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.604219436645508", "y": "9.462596893310547", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618431091308594", "y": "12.962567329406738", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.63264274597168", "y": "16.462539672851562", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 5.55, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4248504638672", "y": "9.170221328735352", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42955017089844", "y": "12.670218467712402", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.43423461914062", "y": "16.170215606689453", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "0", "x": 385.91, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "382.6264343261719", "y": "-235.0435333251953", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "389.6253967285156", "y": "-235.16390991210938", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1248779296875", "y": "-235.22410583496094", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 409.22, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "412.61456298828125", "y": "-85.36454010009766", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61492919921875", "y": "-85.43766784667969", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1151123046875", "y": "-85.47423553466797", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-15.692474365234375", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.6925630569458", "y": "77.76168823242188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192607879638672", "y": "77.74402618408203", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 412.59, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1151123046875", "y": "-85.43630981445312", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61529541015625", "y": "-85.47286987304688", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.115478515625", "y": "-85.50943756103516", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.97, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.157381057739258", "y": "-229.76759338378906", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.662800788879395", "y": "-229.57290649414062", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.168219089508057", "y": "-229.3782196044922", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.59, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858835220336914", "y": "-75.72463989257812", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358861923217773", "y": "-75.7383804321289", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858889102935791", "y": "-75.75211334228516", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.94, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192610740661621", "y": "77.7610855102539", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.692655563354492", "y": "77.74342346191406", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192700386047363", "y": "77.72576141357422", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 11.74, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.124823570251465", "y": "-79.94327545166016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.1248779296875", "y": "-79.91580963134766", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624904632568359", "y": "-79.90206909179688", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 12.33, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.799628257751465", "y": "76.15249633789062", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.79971694946289", "y": "76.18782043457031", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.299761772155762", "y": "76.20548248291016", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 405.54, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1143493652344", "y": "-85.36266326904297", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6141662597656", "y": "-85.32609558105469", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1147155761719", "y": "-85.435791015625", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.31, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858723640441895", "y": "-75.6960678100586", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.35869598388672", "y": "-75.68233489990234", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858777046203613", "y": "-75.72354125976562", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -8.66, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192425727844238", "y": "77.79782104492188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692380905151367", "y": "77.81548309326172", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192514896392822", "y": "77.76249694824219", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.4, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624799728393555", "y": "-79.9426498413086", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124772071838379", "y": "-79.95638275146484", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624853134155273", "y": "-79.91517639160156", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.63, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "12.299577713012695", "y": "76.15148162841797", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79953384399414", "y": "76.13381958007812", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.2996673583984375", "y": "76.18680572509766", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.53, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.847021102905273", "y": "229.667236328125", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.34402847290039", "y": "229.8119354248047", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.853006362915039", "y": "229.37783813476562", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 428.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4712219238281", "y": "432.01580810546875", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.721435546875", "y": "435.5068664550781", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.97076416015625", "y": "425.0337219238281", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 410.82, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.47103881835938", "y": "406.9908752441406", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.74537658691406", "y": "403.50164794921875", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.92237854003906", "y": "413.9693298339844", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -506.72, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1669006347656", "y": "92.98015594482422", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.664794921875", "y": "92.85853576660156", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.1711120605469", "y": "93.223388671875", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -490.77, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.16552734375", "y": "245.8351593017578", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.66729736328125", "y": "245.72369384765625", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1619567871094", "y": "246.05809020996094", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 32.58, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3799743652344", "x": "173.4454803466797", "y": "35.77303695678711", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.38575744628906", "y": "39.272525787353516", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.56495666503906", "y": "28.774057388305664", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 30.78, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2735595703125", "x": "6.096487998962402", "y": "34.107757568359375", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.082276821136475", "y": "37.60772705078125", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.124910831451416", "y": "27.10781478881836", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 30.69, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61404418945312", "y": "33.7061882019043", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6187286376953", "y": "37.20618438720703", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6046600341797", "y": "26.706195831298828", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 29.93, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2468566894531", "y": "33.5247688293457", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.224365234375", "y": "37.024696350097656", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2918701171875", "y": "26.524913787841797", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 17.41, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.5028991699219", "y": "14.132526397705078", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.4099426269531", "y": "10.633761405944824", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.6888732910156", "y": "21.130056381225586", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 14.49, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3299560546875", "y": "10.977312088012695", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3896942138672", "y": "7.477822303771973", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.21047973632812", "y": "17.976293563842773", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 12.92, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575960159301758", "y": "9.462711334228516", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.561748504638672", "y": "5.962739944458008", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.60438346862793", "y": "16.46265411376953", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 12.51, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41551208496094", "y": "9.170232772827148", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41082763671875", "y": "5.670236110687256", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42489624023438", "y": "16.17022705078125", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "0", "x": 389.55, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "386.126953125", "y": "-235.0426788330078", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.62744140625", "y": "-234.98406982421875", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1259765625", "y": "-235.15989685058594", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 402.0, "y": -85.4, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "405.6141662597656", "y": "-85.36223602294922", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "409.1139831542969", "y": "-85.32567596435547", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6138000488281", "y": "-85.28910827636719", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 16.5, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575634002685547", "y": "12.962740898132324", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.56142234802246", "y": "9.462770462036133", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.547210693359375", "y": "5.962799072265625", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 16.9, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41432189941406", "y": "12.67023754119873", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4096221923828", "y": "9.17024040222168", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.40493774414062", "y": "5.670243740081787", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "0", "x": -6.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-9.628252983093262", "y": "-230.17373657226562", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-13.12211799621582", "y": "-230.38087463378906", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.615983963012695", "y": "-230.5880126953125", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-9.358698844909668", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.858672142028809", "y": "-75.68299865722656", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.358644485473633", "y": "-75.66926574707031", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-8.692384719848633", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.192340850830078", "y": "77.8146743774414", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692296028137207", "y": "77.83233642578125", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 4.69, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.12476921081543", "y": "-79.9434814453125", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "11.62474250793457", "y": "-79.95721435546875", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124715805053711", "y": "-79.970947265625", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.29, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.799537658691406", "y": "76.15229034423828", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "12.299492835998535", "y": "76.13462829589844", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79944896697998", "y": "76.1169662475586", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.19, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "9.344169616699219", "y": "229.6626434326172", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.841078758239746", "y": "229.80970764160156", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.337987899780273", "y": "229.95677185058594", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -494.19, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-490.6671142578125", "y": "245.83995056152344", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-487.1688232421875", "y": "245.7306671142578", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.6705322265625", "y": "245.6213836669922", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -503.22, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-506.6645202636719", "y": "92.97496795654297", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-510.1622009277344", "y": "92.84800720214844", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.659912109375", "y": "92.7210464477539", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 393.1, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "389.62744140625", "y": "-235.04331970214844", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "386.1278991699219", "y": "-234.98617553710938", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.6283874511719", "y": "-234.9290313720703", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 425.47, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.46160888671875", "y": "428.5073547363281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.71630859375", "y": "431.9980773925781", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.97100830078125", "y": "435.4888000488281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 414.14, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.45127868652344", "y": "410.49993896484375", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.72093200683594", "y": "407.0103454589844", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.99057006835938", "y": "403.520751953125", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.6, "y": 21.0, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.5164794921875", "y": "17.633331298828125", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.4296569824219", "y": "14.134408950805664", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.3428039550781", "y": "10.635486602783203", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 29.2, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3813171386719", "x": "173.4475555419922", "y": "32.272560119628906", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.3878173828125", "y": "35.77205276489258", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.32809448242188", "y": "39.271541595458984", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "2", "x": 326.5, "y": 20.8, "yaw": 180.0, "z": 1.7 } }, { "transform": { "pitch": "1.490559458732605", "x": "326.55828857421875", "y": "17.38355827331543", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6180114746094", "y": "13.88406753540039", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6777648925781", "y": "10.384577751159668", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 27.4, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2740478515625", "x": "6.096976280212402", "y": "30.607730865478516", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.082764625549316", "y": "34.10770034790039", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.068553447723389", "y": "37.60767364501953", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 27.31, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61387634277344", "y": "30.206186294555664", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6185760498047", "y": "33.70618438720703", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.62326049804688", "y": "37.206180572509766", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 26.55, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.24761962890625", "y": "30.024702072143555", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.22509765625", "y": "33.52463150024414", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.2026062011719", "y": "37.024559020996094", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 18.7, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.34207153320312", "y": "14.47802734375", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4018096923828", "y": "10.978536605834961", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4615478515625", "y": "7.479046821594238", "yaw": "-179.02207946777344", "z": "9.125747680664062" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.33", "y": "-173.27", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "131.66", "y": "-209.1", "yaw": "98.778381", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.92", "y": "-173.39", "yaw": "179.198364", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "92.80", "y": "-170.10", "yaw": "0.12323", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.46", "y": "-170.8", "yaw": "0.453278", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "131.23", "y": "-209.9", "yaw": "98.115265", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "97.61", "y": "-173.41", "yaw": "180.754196", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "58.96", "y": "-208.40", "yaw": "90.754181", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "25.89", "y": "-170.29", "yaw": "1.018799", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "58.81", "y": "-207.71", "yaw": "91.018799", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "97.53", "y": "-173.20", "yaw": "180.886658", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "26.30", "y": "-170.13", "yaw": "0.886627", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "293.32", "y": "-309.45", "yaw": "183.428238", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "259.15", "y": "-271.67", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "221.55", "y": "-307.81", "yaw": "0.056519", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "293.68", "y": "-310.23", "yaw": "182.596146", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "221.79", "y": "-307.84", "yaw": "359.213013", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.92", "y": "-271.79", "yaw": "271.056641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "291.60", "y": "-249.86", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "254.99", "y": "-283.71", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "258.30", "y": "-211.0", "yaw": "272.521973", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.61", "y": "-211.72", "yaw": "270.699127", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "291.96", "y": "-250.4", "yaw": "178.90509", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "220.54", "y": "-246.26", "yaw": "0.699097", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "219.52", "y": "-246.20", "yaw": "0.076721", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.58", "y": "-212.43", "yaw": "270.076752", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "255.6", "y": "-283.25", "yaw": "90.076691", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.8", "y": "-284.50", "yaw": "89.832275", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "220.22", "y": "-246.15", "yaw": "359.832275", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "292.3", "y": "-250.30", "yaw": "179.832275", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.26", "y": "-122.5", "yaw": "180.000015", "z": "1.2" } ], "left": [ { "pitch": "0.0", "x": "254.73", "y": "-154.69", "yaw": "90.0", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "292.83", "y": "-122.44", "yaw": "180.13298", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "221.82", "y": "-120.78", "yaw": "5.250366", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "222.29", "y": "-120.16", "yaw": "1.962585", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "254.68", "y": "-154.78", "yaw": "91.962524", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.99", "y": "9.30", "yaw": "180.317535", "z": "1.0" }, { "pitch": "0.0", "x": "-337.66", "y": "5.69", "yaw": "180.196899", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.5", "y": "16.36", "yaw": "181.84436", "z": "1.0" }, { "pitch": "0.0", "x": "-337.5", "y": "13.9", "yaw": "181.019409", "z": "1.0" }, { "pitch": "0.0", "x": "-336.71", "y": "9.43", "yaw": "180.933701", "z": "1.0" }, { "pitch": "0.0", "x": "-336.38", "y": "5.83", "yaw": "180.079086", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "206.97", "y": "-140.26", "yaw": "257.906311", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "235.73", "y": "-172.75", "yaw": "180.923157", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "166.89", "y": "-169.88", "yaw": "0.923157", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "235.41", "y": "-173.11", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "198.98", "y": "-204.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "205.92", "y": "-142.19", "yaw": "259.577576", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "199.6", "y": "-204.6", "yaw": "91.002838", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "165.6", "y": "-169.56", "yaw": "0.059082", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "235.86", "y": "-173.64", "yaw": "177.911682", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.55", "y": "-169.68", "yaw": "0.490326", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "207.25", "y": "-139.94", "yaw": "258.321381", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "199.18", "y": "-204.78", "yaw": "90.490295", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.33", "y": "-173.27", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "131.66", "y": "-209.1", "yaw": "98.778381", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.92", "y": "-173.39", "yaw": "179.198364", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "92.80", "y": "-170.10", "yaw": "0.12323", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.46", "y": "-170.8", "yaw": "0.453278", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "131.23", "y": "-209.9", "yaw": "98.115265", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "97.61", "y": "-173.41", "yaw": "180.754196", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "58.96", "y": "-208.40", "yaw": "90.754181", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "25.89", "y": "-170.29", "yaw": "1.018799", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "58.81", "y": "-207.71", "yaw": "91.018799", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "97.53", "y": "-173.20", "yaw": "180.886658", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "26.30", "y": "-170.13", "yaw": "0.886627", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "293.32", "y": "-309.45", "yaw": "183.428238", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "259.15", "y": "-271.67", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "221.55", "y": "-307.81", "yaw": "0.056519", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "293.68", "y": "-310.23", "yaw": "182.596146", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "221.79", "y": "-307.84", "yaw": "359.213013", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.92", "y": "-271.79", "yaw": "271.056641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "291.60", "y": "-249.86", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "254.99", "y": "-283.71", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "258.30", "y": "-211.0", "yaw": "272.521973", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.61", "y": "-211.72", "yaw": "270.699127", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "291.96", "y": "-250.4", "yaw": "178.90509", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "220.54", "y": "-246.26", "yaw": "0.699097", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "219.52", "y": "-246.20", "yaw": "0.076721", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.58", "y": "-212.43", "yaw": "270.076752", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "255.6", "y": "-283.25", "yaw": "90.076691", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.8", "y": "-284.50", "yaw": "89.832275", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "220.22", "y": "-246.15", "yaw": "359.832275", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "292.3", "y": "-250.30", "yaw": "179.832275", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.26", "y": "-122.5", "yaw": "180.000015", "z": "1.2" } ], "left": [ { "pitch": "0.0", "x": "254.73", "y": "-154.69", "yaw": "90.0", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "292.83", "y": "-122.44", "yaw": "180.13298", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "221.82", "y": "-120.78", "yaw": "5.250366", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "222.29", "y": "-120.16", "yaw": "1.962585", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "254.68", "y": "-154.78", "yaw": "91.962524", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.99", "y": "9.30", "yaw": "180.317535", "z": "1.0" }, { "pitch": "0.0", "x": "-337.66", "y": "5.69", "yaw": "180.196899", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.5", "y": "16.36", "yaw": "181.84436", "z": "1.0" }, { "pitch": "0.0", "x": "-337.5", "y": "13.9", "yaw": "181.019409", "z": "1.0" }, { "pitch": "0.0", "x": "-336.71", "y": "9.43", "yaw": "180.933701", "z": "1.0" }, { "pitch": "0.0", "x": "-336.38", "y": "5.83", "yaw": "180.079086", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "206.97", "y": "-140.26", "yaw": "257.906311", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "235.73", "y": "-172.75", "yaw": "180.923157", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "166.89", "y": "-169.88", "yaw": "0.923157", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "235.41", "y": "-173.11", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "198.98", "y": "-204.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "205.92", "y": "-142.19", "yaw": "259.577576", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "199.6", "y": "-204.6", "yaw": "91.002838", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "165.6", "y": "-169.56", "yaw": "0.059082", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "235.86", "y": "-173.64", "yaw": "177.911682", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.55", "y": "-169.68", "yaw": "0.490326", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "207.25", "y": "-139.94", "yaw": "258.321381", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "199.18", "y": "-204.78", "yaw": "90.490295", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.33", "y": "-173.27", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "131.66", "y": "-209.1", "yaw": "98.778381", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "97.61", "y": "-173.41", "yaw": "180.754196", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "58.96", "y": "-208.40", "yaw": "90.754181", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "221.79", "y": "-307.84", "yaw": "359.213013", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.92", "y": "-271.79", "yaw": "271.056641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.26", "y": "-122.5", "yaw": "180.000015", "z": "1.2" } ], "left": [ { "pitch": "0.0", "x": "254.73", "y": "-154.69", "yaw": "90.0", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.92", "y": "-173.39", "yaw": "179.198364", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "92.80", "y": "-170.10", "yaw": "0.12323", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.46", "y": "-170.8", "yaw": "0.453278", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "131.23", "y": "-209.9", "yaw": "98.115265", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "25.89", "y": "-170.29", "yaw": "1.018799", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "58.81", "y": "-207.71", "yaw": "91.018799", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "97.53", "y": "-173.20", "yaw": "180.886658", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "26.30", "y": "-170.13", "yaw": "0.886627", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "293.32", "y": "-309.45", "yaw": "183.428238", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "259.15", "y": "-271.67", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "221.55", "y": "-307.81", "yaw": "0.056519", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "293.68", "y": "-310.23", "yaw": "182.596146", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "292.83", "y": "-122.44", "yaw": "180.13298", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "221.82", "y": "-120.78", "yaw": "5.250366", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "222.29", "y": "-120.16", "yaw": "1.962585", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "254.68", "y": "-154.78", "yaw": "91.962524", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.99", "y": "9.30", "yaw": "180.317535", "z": "1.0" }, { "pitch": "0.0", "x": "-337.66", "y": "5.69", "yaw": "180.196899", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "291.60", "y": "-249.86", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "254.99", "y": "-283.71", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "258.30", "y": "-211.0", "yaw": "272.521973", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.61", "y": "-211.72", "yaw": "270.699127", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "291.96", "y": "-250.4", "yaw": "178.90509", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "220.54", "y": "-246.26", "yaw": "0.699097", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "219.52", "y": "-246.20", "yaw": "0.076721", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.58", "y": "-212.43", "yaw": "270.076752", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "255.6", "y": "-283.25", "yaw": "90.076691", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.8", "y": "-284.50", "yaw": "89.832275", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "220.22", "y": "-246.15", "yaw": "359.832275", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "292.3", "y": "-250.30", "yaw": "179.832275", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "206.97", "y": "-140.26", "yaw": "257.906311", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "235.73", "y": "-172.75", "yaw": "180.923157", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "166.89", "y": "-169.88", "yaw": "0.923157", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "235.41", "y": "-173.11", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "198.98", "y": "-204.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "205.92", "y": "-142.19", "yaw": "259.577576", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "199.6", "y": "-204.6", "yaw": "91.002838", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "165.6", "y": "-169.56", "yaw": "0.059082", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "235.86", "y": "-173.64", "yaw": "177.911682", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.55", "y": "-169.68", "yaw": "0.490326", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "207.25", "y": "-139.94", "yaw": "258.321381", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "199.18", "y": "-204.78", "yaw": "90.490295", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario10" } ], "Town05": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.73, "y": 145.88, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 55.87, "y": -145.22, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 101.5, "y": 137.98, "yaw": 164.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.81, "y": 142.49, "yaw": 344.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 136.31, "y": 121.37, "yaw": 137.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 137.75, "y": 125.7, "yaw": 317.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 149.54, "y": 101.12, "yaw": 107.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 152.94, "y": 104.16, "yaw": 287.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": 49.67, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": 51.39, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.37, "y": 16.76, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.55, "y": -16.99, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": -59.22, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": -57.49, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 150.46, "y": -102.24, "yaw": 76.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 154.95, "y": -101.44, "yaw": 255.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 134.58, "y": -127.97, "yaw": 46.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 138.88, "y": -129.5, "yaw": 225.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 98.27, "y": -141.73, "yaw": 11.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.88, "y": -145.47, "yaw": 190.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0", "x": -240.52, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.52142333984375", "y": "-76.91566467285156", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.5221405029297", "y": "-76.96470642089844", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.39, "y": 201.6, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-124.4139175415039", "y": "34.73600387573242", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.6", "y": "29.6", "yaw": "268.398804", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "120.28", "y": "2.26", "yaw": "358.398743", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "151.62", "y": "-30.72", "yaw": "88.888824", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "120.37", "y": "2.29", "yaw": "358.888824", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "151.22", "y": "-30.42", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "155.36", "y": "29.78", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.6", "y": "29.6", "yaw": "268.398804", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "120.28", "y": "2.26", "yaw": "358.398743", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "202.40", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.22", "y": "154.61", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "202.40", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.22", "y": "154.61", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "202.40", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.22", "y": "154.61", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.55", "y": "202.25", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.5", "y": "155.19", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.55", "y": "202.25", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.5", "y": "155.19", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.55", "y": "202.25", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.5", "y": "155.19", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "151.62", "y": "-30.72", "yaw": "88.888824", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "120.37", "y": "2.29", "yaw": "358.888824", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.20", "y": "-200.72", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.18", "y": "-151.85", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.20", "y": "-200.72", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.18", "y": "-151.85", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.20", "y": "-200.72", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.18", "y": "-151.85", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "-200.77", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.53", "y": "-152.61", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "-200.77", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.53", "y": "-152.61", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "-200.77", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.53", "y": "-152.61", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "151.22", "y": "-30.42", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "155.36", "y": "29.78", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-124.4139175415039", "y": "34.73600387573242", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } } ], "scenario_type": "Scenario10" } ], "Town06": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 669.39, "y": 83.38, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "672.7225952148438", "y": "83.4161376953125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7229614257812", "y": "83.34022521972656", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2232055664062", "y": "83.30226135253906", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.723388671875", "y": "83.2643051147461", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.7, "y": 83.5, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.2218627929688", "y": "83.46227264404297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7220458984375", "y": "83.42431640625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2222900390625", "y": "83.3863525390625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7224731445312", "y": "83.34839630126953", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.3, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-8.675992965698242", "y": "-53.622528076171875", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.0, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.176236152648926", "y": "-53.574485778808594", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 2.4, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.828932285308838", "y": "20.622880935668945", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.9, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.3291661739349365", "y": "20.576173782348633", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -16.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-20.065515518188477", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.5749969482422", "y": "-23.56549072265625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-13.065561294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -20.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-23.56553840637207", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-16.565584182739258", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6259765625", "y": "-13.065608024597168", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -23.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.6136016845703", "y": "-20.065608978271484", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.62635803222656", "y": "-16.565631866455078", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.63909912109375", "y": "-13.065655708312988", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -12.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187618255615234", "y": "-16.09782600402832", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.174869537353516", "y": "-19.597803115844727", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -16.1, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187252044677734", "y": "-19.597848892211914", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.212745666503906", "y": "-12.597894668579102", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.91, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.90859985351562", "y": "45.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9071807861328", "y": "48.9715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.90577697753906", "y": "52.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.92, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.91854858398438", "y": "48.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.91714477539062", "y": "52.47157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.92138671875", "y": "41.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9285888671875", "y": "52.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93141174316406", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93283081054688", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 52.88, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9315643310547", "y": "48.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9329833984375", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9344024658203", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -19.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.21311569213867", "y": "-16.097919464111328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.225860595703125", "y": "-12.597942352294922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 658.6, "y": 82.95, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "662.2265625", "y": "82.98932647705078", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.726318359375", "y": "83.02729034423828", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2261352539062", "y": "83.06524658203125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7259521484375", "y": "83.10320281982422", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 662.3, "y": 83.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "665.7197265625", "y": "83.63709259033203", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2195434570312", "y": "83.675048828125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7193603515625", "y": "83.71300506591797", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7201538085938", "y": "83.56117248535156", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.8, "y": 83.17, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.224609375", "y": "83.20713806152344", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7244262695312", "y": "83.2450942993164", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2250366210938", "y": "83.13121795654297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7252197265625", "y": "83.09326171875", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.4, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "12.778694152832031", "y": "276.646728515625", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.77956485748291", "y": "276.75714111328125", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 239.9, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.6988410949707", "y": "243.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68668746948242", "y": "246.61331176757812", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.674537658691406", "y": "250.11329650878906", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -10.2, "y": 213.5, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.720656394958496", "y": "213.4451141357422", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2210917472839355", "y": "213.38990783691406", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6298828125", "y": "138.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6454467773438", "y": "138.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 657.7, "y": 183.15, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "661.1398315429688", "y": "183.1873016357422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6395874023438", "y": "183.2252655029297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.139404296875", "y": "183.2632293701172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6392211914062", "y": "183.30117797851562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 661.7, "y": 183.26, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "664.6388549804688", "y": "183.2918701171875", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.138671875", "y": "183.329833984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6384887695312", "y": "183.36778259277344", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6392822265625", "y": "183.21595764160156", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.658935546875", "y": "138.49703979492188", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.2, "y": 183.37, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.137939453125", "y": "183.40187072753906", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6377563476562", "y": "183.4398193359375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1383666992188", "y": "183.32594299316406", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6385498046875", "y": "183.28799438476562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 668.99, "y": 183.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "671.6359252929688", "y": "183.60870361328125", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6362915039062", "y": "183.5327911376953", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1365356445312", "y": "183.4948272705078", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.63671875", "y": "183.45687866210938", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.3, "y": 183.7, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.1351928710938", "y": "183.6548309326172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6353759765625", "y": "183.6168670654297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1356201171875", "y": "183.5789031982422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6358032226562", "y": "183.54095458984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -13.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58847045898438", "y": "-16.565494537353516", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.57571411132812", "y": "-20.065471649169922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.56297302246094", "y": "-23.565448760986328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.278183937072754", "y": "276.6419982910156", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.777749061584473", "y": "276.5867919921875", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3915710449219", "y": "45.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3932800292969", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39495849609375", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3915100097656", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3931884765625", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3880920410156", "y": "41.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3863830566406", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39154052734375", "y": "52.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "45.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3864440917969", "y": "41.744102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3847351074219", "y": "38.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 52.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.27813720703125", "y": "48.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27642822265625", "y": "45.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27471923828125", "y": "41.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27301025390625", "y": "38.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.4, "y": 138.59, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.39260864257812", "y": "135.4395294189453", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.49070739746094", "y": "138.93931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.48249816894531", "y": "135.43931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -239.6, "y": 240.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-239.59410095214844", "y": "243.68092346191406", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58779907226562", "y": "247.180908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58151245117188", "y": "250.680908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -359.5, "y": 58.1, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-362.68389892578125", "y": "57.73311233520508", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-366.160888671875", "y": "57.33245086669922", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.63787841796875", "y": "56.931793212890625", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -13.9, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.298583984375", "y": "-17.034290313720703", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28582763671875", "y": "-20.53426742553711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.2731018066406", "y": "-24.034242630004883", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 503.51, "y": -10.4, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "503.5177307128906", "y": "-13.939313888549805", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5253601074219", "y": "-17.439306259155273", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.53302001953125", "y": "-20.93929672241211", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5406494140625", "y": "-24.439289093017578", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 38.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.401611328125", "y": "41.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.405029296875", "y": "48.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4067077636719", "y": "52.24409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 38.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.40155029296875", "y": "41.81858444213867", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40325927734375", "y": "45.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40496826171875", "y": "48.818580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40667724609375", "y": "52.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 41.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29331970214844", "y": "45.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29661560058594", "y": "48.73708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29991149902344", "y": "52.23708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 138.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3869323730469", "y": "141.3854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3725891113281", "y": "144.8854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3582458496094", "y": "148.38539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3439025878906", "y": "151.88536071777344", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 137.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3870544433594", "y": "140.75856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3727111816406", "y": "144.25852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3583679199219", "y": "147.7584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3440246582031", "y": "151.2584686279297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.3, "y": 136.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "140.13125610351562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2720184326172", "y": "143.6312255859375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.25767517089844", "y": "147.13119506835938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2433319091797", "y": "150.63116455078125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.1, "y": 135.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 333.2, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1989440917969", "y": "241.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.19775390625", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.196533203125", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1953430175781", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89891052246094", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89772033691406", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8965301513672", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8953399658203", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 238.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09896469116211", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09777069091797", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.096576690673828", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.095382690429688", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 669.39, "y": 83.38, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7225952148438", "y": "83.4161376953125", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.7229614257812", "y": "83.34022521972656", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2232055664062", "y": "83.30226135253906", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.723388671875", "y": "83.2643051147461", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 672.7, "y": 83.5, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.2218627929688", "y": "83.46227264404297", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.7220458984375", "y": "83.42431640625", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2222900390625", "y": "83.3863525390625", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.7224731445312", "y": "83.34839630126953", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "48.99", "y": "-12.63", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.2", "y": "-16.23", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.4", "y": "-19.73", "yaw": "180.396667", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.3, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "48.99", "y": "-12.63", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.2", "y": "-16.23", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.4", "y": "-19.73", "yaw": "180.396667", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-8.675992965698242", "y": "-53.622528076171875", "yaw": "90.3823013305664", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.40", "y": "-12.63", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.47", "y": "-16.13", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.48", "y": "-19.63", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.4, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.40", "y": "-12.63", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.47", "y": "-16.13", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.48", "y": "-19.63", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.828932285308838", "y": "20.622880935668945", "yaw": "270.3822937011719", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.32", "y": "-12.69", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.46", "y": "-16.19", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.52", "y": "-19.69", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.9, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.32", "y": "-12.69", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.46", "y": "-16.19", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.52", "y": "-19.69", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.3291661739349365", "y": "20.576173782348633", "yaw": "270.3822937011719", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.54", "y": "4.45", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "4.87", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.49", "y": "89.92", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.99", "y": "90.38", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.81, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.54", "y": "4.45", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "4.87", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.49", "y": "89.92", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.99", "y": "90.38", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.80860137939453", "y": "45.41740798950195", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.54", "y": "4.45", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "4.87", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.49", "y": "89.92", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.99", "y": "90.38", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.807186126708984", "y": "48.91740798950195", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.57", "y": "5.13", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.7", "y": "5.16", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.46", "y": "90.7", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.96", "y": "90.5", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.82, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.57", "y": "5.13", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.7", "y": "5.16", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.46", "y": "90.7", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.96", "y": "90.5", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.81857681274414", "y": "48.91741180419922", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.57", "y": "5.13", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.7", "y": "5.16", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.46", "y": "90.7", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.96", "y": "90.5", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.821407318115234", "y": "41.91741180419922", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -16.7, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-20.065515518188477", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.5749969482422", "y": "-23.56549072265625", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-13.065561294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -20.2, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-23.56553840637207", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-16.565584182739258", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6259765625", "y": "-13.065608024597168", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -23.8, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6136016845703", "y": "-20.065608978271484", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.62635803222656", "y": "-16.565631866455078", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.63909912109375", "y": "-13.065655708312988", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.54", "y": "24.96", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.54", "y": "24.53", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.25", "y": "-60.50", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.75", "y": "-60.95", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 44.2, "y": -12.7, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.54", "y": "24.96", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.54", "y": "24.53", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.25", "y": "-60.50", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.75", "y": "-60.95", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.187618255615234", "y": "-16.09782600402832", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.54", "y": "24.96", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.54", "y": "24.53", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.25", "y": "-60.50", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.75", "y": "-60.95", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.174869537353516", "y": "-19.597803115844727", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.57", "y": "24.28", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.57", "y": "24.24", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.22", "y": "-60.65", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.72", "y": "-60.62", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 44.2, "y": -16.1, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.57", "y": "24.28", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.57", "y": "24.24", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.22", "y": "-60.65", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.72", "y": "-60.62", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.187252044677734", "y": "-19.597848892211914", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.57", "y": "24.28", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.57", "y": "24.24", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.22", "y": "-60.65", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.72", "y": "-60.62", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.212745666503906", "y": "-12.597894668579102", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.91, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.90859985351562", "y": "45.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9071807861328", "y": "48.9715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.90577697753906", "y": "52.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.92, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.91854858398438", "y": "48.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.91714477539062", "y": "52.47157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.92138671875", "y": "41.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.93, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9285888671875", "y": "52.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.93141174316406", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.93283081054688", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.93, "y": 52.88, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9315643310547", "y": "48.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9329833984375", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9344024658203", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.60", "y": "24.37", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.60", "y": "24.39", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.18", "y": "-60.36", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.69", "y": "-61.16", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 44.2, "y": -19.7, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.60", "y": "24.37", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.60", "y": "24.39", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.18", "y": "-60.36", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.69", "y": "-61.16", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.21311569213867", "y": "-16.097919464111328", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.60", "y": "24.37", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.60", "y": "24.39", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.18", "y": "-60.36", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.69", "y": "-61.16", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.225860595703125", "y": "-12.597942352294922", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 658.6, "y": 82.95, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2265625", "y": "82.98932647705078", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.726318359375", "y": "83.02729034423828", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.2261352539062", "y": "83.06524658203125", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7259521484375", "y": "83.10320281982422", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 662.3, "y": 83.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.7197265625", "y": "83.63709259033203", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.2195434570312", "y": "83.675048828125", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7193603515625", "y": "83.71300506591797", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.7201538085938", "y": "83.56117248535156", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 665.8, "y": 83.17, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.224609375", "y": "83.20713806152344", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7244262695312", "y": "83.2450942993164", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2250366210938", "y": "83.13121795654297", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.7252197265625", "y": "83.09326171875", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.60", "y": "5.4", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.10", "y": "5.1", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.42", "y": "89.78", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.93", "y": "90.59", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.83, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.60", "y": "5.4", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.10", "y": "5.1", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.42", "y": "89.78", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.93", "y": "90.59", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.83143615722656", "y": "45.41741943359375", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.60", "y": "5.4", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.10", "y": "5.1", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.42", "y": "89.78", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.93", "y": "90.59", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.83285140991211", "y": "41.91741943359375", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-52.21", "y": "41.88", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.24", "y": "45.48", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.28", "y": "48.98", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 1.96, "y": 83.3, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-52.21", "y": "41.88", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.24", "y": "45.48", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.28", "y": "48.98", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.747596740722656", "y": "83.26728820800781", "yaw": "269.5051574707031", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-51.93", "y": "41.86", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.96", "y": "45.46", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.0", "y": "48.96", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.66, "y": 83.4, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-51.93", "y": "41.86", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.96", "y": "45.46", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.0", "y": "48.96", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.2488670349121094", "y": "83.4294662475586", "yaw": "269.5051574707031", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.18", "y": "42.22", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.72", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.20", "y": "49.22", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.51, "y": 10.56, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.18", "y": "42.22", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.72", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.20", "y": "49.22", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.104096412658691", "y": "10.536018371582031", "yaw": "90.3823013305664", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.10", "y": "42.28", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.78", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.24", "y": "49.28", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.0, "y": 10.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.10", "y": "42.28", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.78", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.24", "y": "49.28", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.604596138000488", "y": "10.62265682220459", "yaw": "90.3823013305664", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "207.99", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.60", "y": "208.3", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-41.5", "y": "239.29", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-41.1", "y": "242.79", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 9.4, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "207.99", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.60", "y": "208.3", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-41.5", "y": "239.29", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-41.1", "y": "242.79", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "12.778694152832031", "y": "276.646728515625", "yaw": "-90.90380859375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "207.99", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.60", "y": "208.3", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-41.5", "y": "239.29", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-41.1", "y": "242.79", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "5.77956485748291", "y": "276.75714111328125", "yaw": "-90.90380859375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 239.9, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.6988410949707", "y": "243.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68668746948242", "y": "246.61331176757812", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.674537658691406", "y": "250.11329650878906", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "138.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-40.11", "y": "239.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.10", "y": "243.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.8", "y": "247.10", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.7", "y": "250.60", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -10.2, "y": 213.5, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-40.11", "y": "239.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.10", "y": "243.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.8", "y": "247.10", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.7", "y": "250.60", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.720656394958496", "y": "213.4451141357422", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-40.11", "y": "239.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.10", "y": "243.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.8", "y": "247.10", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.7", "y": "250.60", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2210917472839355", "y": "213.38990783691406", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6298828125", "y": "138.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6454467773438", "y": "138.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 657.7, "y": 183.15, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1398315429688", "y": "183.1873016357422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6395874023438", "y": "183.2252655029297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.139404296875", "y": "183.2632293701172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6392211914062", "y": "183.30117797851562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 661.7, "y": 183.26, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6388549804688", "y": "183.2918701171875", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.138671875", "y": "183.329833984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6384887695312", "y": "183.36778259277344", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.6392822265625", "y": "183.21595764160156", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.658935546875", "y": "138.49703979492188", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 665.2, "y": 183.37, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.137939453125", "y": "183.40187072753906", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6377563476562", "y": "183.4398193359375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1383666992188", "y": "183.32594299316406", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.6385498046875", "y": "183.28799438476562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 668.99, "y": 183.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6359252929688", "y": "183.60870361328125", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6362915039062", "y": "183.5327911376953", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1365356445312", "y": "183.4948272705078", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.63671875", "y": "183.45687866210938", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 672.3, "y": 183.7, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.1351928710938", "y": "183.6548309326172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6353759765625", "y": "183.6168670654297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1356201171875", "y": "183.5789031982422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.6358032226562", "y": "183.54095458984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -13.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.58847045898438", "y": "-16.565494537353516", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.57571411132812", "y": "-20.065471649169922", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.56297302246094", "y": "-23.565448760986328", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.23", "y": "207.94", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.72", "y": "207.98", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-40.85", "y": "239.24", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-40.81", "y": "242.74", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.23", "y": "207.94", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.72", "y": "207.98", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-40.85", "y": "239.24", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-40.81", "y": "242.74", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "9.278183937072754", "y": "276.6419982910156", "yaw": "-90.90380859375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.23", "y": "207.94", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.72", "y": "207.98", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-40.85", "y": "239.24", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-40.81", "y": "242.74", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "12.777749061584473", "y": "276.5867919921875", "yaw": "-90.90380859375", "z": "0.0" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [], "scenario_type": "Scenario10" } ] } ] } ================================================ FILE: leaderboard/data/scenarios/longest6_eval_scenarios.json ================================================ { "available_scenarios": [ { "Town01": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [], "scenario_type": "Scenario2" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "167.69", "y": "1.93", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "165.10", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "373.9", "y": "-2.4", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.53", "y": "37.27", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "234.28", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "199.78", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "168.51", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "134.1", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "94.27", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "59.77", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.24", "y": "-1.87", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "158.80", "y": "36.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.17", "y": "-1.91", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "92.99", "y": "35.91", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "87.99", "y": "20.43", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.87", "y": "55.22", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.47", "y": "94.86", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.56", "y": "129.21", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.35", "y": "160.10", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "127.21", "y": "195.29", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.28", "y": "59.38", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "153.78", "y": "20.38", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "53.0", "y": "330.25", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.86", "y": "292.27", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "300.57", "y": "331.2", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "334.60", "y": "291.92", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [], "scenario_type": "Scenario5" }, { "available_event_configurations": [], "scenario_type": "Scenario6" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.25", "y": "160.22", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "338.75", "y": "234.22", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.25", "y": "160.22", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "338.75", "y": "234.22", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "373.9", "y": "-2.4", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.53", "y": "37.27", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "234.28", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "199.78", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "168.51", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "134.1", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "94.27", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "59.77", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.24", "y": "-1.87", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "158.80", "y": "36.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.17", "y": "-1.91", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "92.99", "y": "35.91", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "87.99", "y": "20.43", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.87", "y": "55.22", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.47", "y": "94.86", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.56", "y": "129.21", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.35", "y": "160.10", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "127.21", "y": "195.29", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.28", "y": "59.38", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "153.78", "y": "20.38", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "53.0", "y": "330.25", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.86", "y": "292.27", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "300.57", "y": "331.2", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "334.60", "y": "291.92", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [], "scenario_type": "Scenario10" } ], "Town02": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [], "scenario_type": "Scenario2" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.28", "y": "161.41", "yaw": "90.0", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "23.72", "y": "187.41", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [], "scenario_type": "Scenario5" }, { "available_event_configurations": [], "scenario_type": "Scenario6" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.28", "y": "161.41", "yaw": "90.0", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "23.72", "y": "187.41", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [], "scenario_type": "Scenario10" } ], "Town03": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -44.77, "y": 197.2, "yaw": 187.0, "z": 1.74 } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0.0", "x": "-73.64797973632812", "y": "165.80230712890625", "yaw": "257.414306640625", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -77.8, "y": 34.5, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.094234466552734", "y": "69.08776092529297", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 244.44, "y": 44.28, "yaw": 271.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "241.04603576660156", "y": "44.19745635986328", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 46.52, "y": -196.33, "yaw": 1.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "46.43220520019531", "y": "-192.8362274169922", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.6, "y": -163.36, "yaw": 91.0, "z": 1.82 } }, { "transform": { "pitch": "360.0", "x": "-3.4487547874450684", "y": "-163.4599151611328", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } }, { "transform": { "pitch": "360.0", "x": "244.55511474609375", "y": "43.866703033447266", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -37.73, "y": 0.99, "yaw": 7.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 32.76, "y": -8.17, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.66706466674805", "y": "-4.5203680992126465", "yaw": "181.4586181640625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.45, "y": -4.56, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.539730072021484", "y": "-8.024791717529297", "yaw": "181.48350524902344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [], "scenario_type": "Scenario2" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": {}, "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "28.78", "y": "196.68", "yaw": "180.072144", "z": "0.99" }, { "pitch": "0.0", "x": "27.30", "y": "193.64", "yaw": "180.072144", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [], "scenario_type": "Scenario5" }, { "available_event_configurations": [], "scenario_type": "Scenario6" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "11.706635", "x": "150.69", "y": "-164.90", "yaw": "91.510803", "z": "5.2" } ], "right": [ { "pitch": "358.462036", "x": "153.26", "y": "-100.40", "yaw": "271.510834", "z": "9.82" } ] }, "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.55", "y": "98.97", "yaw": "270.182343", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.18", "y": "33.11", "yaw": "90.185455", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-120.9", "y": "41.36", "yaw": "134.365295", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -149.58, "y": 40.72, "yaw": 90.0, "z": 0.99 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-120.27", "y": "40.79", "yaw": "133.405731", "z": "0.99" }, { "pitch": "0.0", "x": "-110.74", "y": "25.41", "yaw": "133.243774", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.9", "y": "100.67", "yaw": "267.650696", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.8", "y": "33.43", "yaw": "89.421509", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "109.25", "y": "-6.99", "yaw": "181.86908", "z": "1.54" } ] }, "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "182.92", "y": "-6.10", "yaw": "181.491562", "z": "1.38" } ] }, "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "11.706635", "x": "150.69", "y": "-164.90", "yaw": "91.510803", "z": "5.2" } ], "right": [ { "pitch": "358.462036", "x": "153.26", "y": "-100.40", "yaw": "271.510834", "z": "9.82" } ] }, "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.55", "y": "98.97", "yaw": "270.182343", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.18", "y": "33.11", "yaw": "90.185455", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-120.9", "y": "41.36", "yaw": "134.365295", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -149.58, "y": 40.72, "yaw": 90.0, "z": 0.99 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-120.27", "y": "40.79", "yaw": "133.405731", "z": "0.99" }, { "pitch": "0.0", "x": "-110.74", "y": "25.41", "yaw": "133.243774", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.9", "y": "100.67", "yaw": "267.650696", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-149.8", "y": "33.43", "yaw": "89.421509", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "78.2", "y": "-41.38", "yaw": "90.581818", "z": "5.74" } ] }, "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "109.25", "y": "-6.99", "yaw": "181.86908", "z": "1.54" } ] }, "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "other_actors": { "left": [ { "pitch": "0.237915", "x": "182.92", "y": "-6.10", "yaw": "181.491562", "z": "1.38" } ] }, "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "148.59", "y": "-40.93", "yaw": "90.603851", "z": "5.25" } ] }, "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "28.78", "y": "196.68", "yaw": "180.072144", "z": "0.99" }, { "pitch": "0.0", "x": "27.30", "y": "193.64", "yaw": "180.072144", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario10" } ], "Town04": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -333.24, "y": 435.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-332.98760986328125", "y": "432.04986572265625", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7461853027344", "y": "428.5581970214844", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.5047607421875", "y": "425.0665283203125", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 406.92, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.44630432128906", "y": "403.47784423828125", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.88621520996094", "y": "410.4554138183594", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.60617065429688", "y": "413.9441833496094", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -183.17, "y": 403.29, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-182.87094116210938", "y": "406.9427185058594", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.58535766601562", "y": "410.4310302734375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.29977416992188", "y": "413.91937255859375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -510.3, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-513.669189453125", "y": "92.98770141601562", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6730651855469", "y": "93.22088623046875", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17498779296875", "y": "93.33748626708984", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -514.1, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1750793457031", "y": "93.2253189086914", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6768493652344", "y": "93.33702087402344", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17864990234375", "y": "93.44872283935547", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -13.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-16.640460968017578", "y": "-230.1665802001953", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.651756286621094", "y": "-229.7690887451172", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.15740442276001", "y": "-229.57032775878906", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -487.27, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-483.66375732421875", "y": "245.8326873779297", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6600646972656", "y": "246.06027221679688", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1582336425781", "y": "246.17405700683594", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -483.59, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.15789794921875", "y": "246.0686798095703", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6559753417969", "y": "246.1850128173828", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1540222167969", "y": "246.30136108398438", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -9.69, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.133902549743652", "y": "-230.1801300048828", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.628005981445312", "y": "-230.38319396972656", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.145692825317383", "y": "-229.77401733398438", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 13.24, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "16.350406646728516", "y": "229.65643310546875", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.356184005737305", "y": "229.37210083007812", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.859072208404541", "y": "229.2299346923828", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.3, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624905586242676", "y": "-79.91557312011719", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.124932289123535", "y": "-79.90184020996094", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624959468841553", "y": "-79.88809967041016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.9, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": 16.8, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.859013557434082", "y": "229.3724365234375", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.361806869506836", "y": "229.2326202392578", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.864601135253906", "y": "229.09280395507812", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 432.39, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4604797363281", "y": "435.5253601074219", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.9693603515625", "y": "428.5426025390625", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7237854003906", "y": "425.0512390136719", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 36.18, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3785705566406", "x": "173.44720458984375", "y": "39.27357482910156", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.56666564941406", "y": "32.274593353271484", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.62640380859375", "y": "28.775104522705078", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 34.38, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2730407714844", "x": "6.096894264221191", "y": "37.6077880859375", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.125317096710205", "y": "30.607847213745117", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.139528274536133", "y": "27.10787582397461", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 34.29, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6138916015625", "y": "37.20619201660156", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60450744628906", "y": "30.206199645996094", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.59982299804688", "y": "26.70620346069336", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 33.53, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.24749755859375", "y": "37.024845123291016", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.2925109863281", "y": "30.02499008178711", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.31500244140625", "y": "26.525062561035156", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 39.53, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.37725830078125", "x": "173.5640869140625", "y": "35.775062561035156", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.6238250732422", "y": "32.275569915771484", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.68356323242188", "y": "28.776081085205078", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 37.73, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2725524902344", "x": "6.124706745147705", "y": "34.107872009277344", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.138918399810791", "y": "30.60790252685547", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.153129577636719", "y": "27.10793113708496", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 37.64, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60472106933594", "y": "33.70620346069336", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6000213623047", "y": "30.206205368041992", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.5953369140625", "y": "26.706209182739258", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 36.88, "yaw": 359.0, "z": 1.13 } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.2915344238281", "y": "33.52505874633789", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3140563964844", "y": "30.025129318237305", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3365478515625", "y": "26.52520179748535", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "0", "x": -12.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.358753204345703", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358806610107422", "y": "-75.72421264648438", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.8588337898254395", "y": "-75.73794555664062", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 14.1, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.49053955078125", "y": "10.631532669067383", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.69122314453125", "y": "17.62865447998047", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.79156494140625", "y": "21.127216339111328", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 11.9, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.3455047607422", "y": "7.477066993713379", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.2260284423828", "y": "14.47604751586914", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.16629028320312", "y": "17.97553825378418", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 9.52, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618186950683594", "y": "16.46259880065918", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 9.11, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41539001464844", "y": "5.670230388641357", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42477416992188", "y": "12.6702241897583", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42945861816406", "y": "16.17022132873535", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 10.45, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.70556640625", "y": "14.126648902893066", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.8155212402344", "y": "17.624921798706055", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.92547607421875", "y": "21.123193740844727", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 7.53, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.215087652206421", "x": "156.21119689941406", "y": "10.975284576416016", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.15145874023438", "y": "14.474775314331055", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.0917205810547", "y": "17.974266052246094", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 5.96, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.604219436645508", "y": "9.462596893310547", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618431091308594", "y": "12.962567329406738", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.63264274597168", "y": "16.462539672851562", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 5.55, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4248504638672", "y": "9.170221328735352", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42955017089844", "y": "12.670218467712402", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.43423461914062", "y": "16.170215606689453", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "0", "x": 385.91, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "382.6264343261719", "y": "-235.0435333251953", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "389.6253967285156", "y": "-235.16390991210938", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1248779296875", "y": "-235.22410583496094", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 409.22, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "412.61456298828125", "y": "-85.36454010009766", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61492919921875", "y": "-85.43766784667969", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1151123046875", "y": "-85.47423553466797", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-15.692474365234375", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.6925630569458", "y": "77.76168823242188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192607879638672", "y": "77.74402618408203", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 412.59, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1151123046875", "y": "-85.43630981445312", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61529541015625", "y": "-85.47286987304688", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.115478515625", "y": "-85.50943756103516", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.97, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.157381057739258", "y": "-229.76759338378906", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.662800788879395", "y": "-229.57290649414062", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.168219089508057", "y": "-229.3782196044922", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.59, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858835220336914", "y": "-75.72463989257812", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358861923217773", "y": "-75.7383804321289", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858889102935791", "y": "-75.75211334228516", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.94, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192610740661621", "y": "77.7610855102539", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.692655563354492", "y": "77.74342346191406", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192700386047363", "y": "77.72576141357422", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 11.74, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.124823570251465", "y": "-79.94327545166016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.1248779296875", "y": "-79.91580963134766", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624904632568359", "y": "-79.90206909179688", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 12.33, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.799628257751465", "y": "76.15249633789062", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.79971694946289", "y": "76.18782043457031", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.299761772155762", "y": "76.20548248291016", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 405.54, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1143493652344", "y": "-85.36266326904297", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6141662597656", "y": "-85.32609558105469", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1147155761719", "y": "-85.435791015625", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.31, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858723640441895", "y": "-75.6960678100586", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.35869598388672", "y": "-75.68233489990234", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858777046203613", "y": "-75.72354125976562", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -8.66, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192425727844238", "y": "77.79782104492188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692380905151367", "y": "77.81548309326172", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192514896392822", "y": "77.76249694824219", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.4, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624799728393555", "y": "-79.9426498413086", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124772071838379", "y": "-79.95638275146484", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624853134155273", "y": "-79.91517639160156", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.63, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "12.299577713012695", "y": "76.15148162841797", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79953384399414", "y": "76.13381958007812", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.2996673583984375", "y": "76.18680572509766", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.53, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.847021102905273", "y": "229.667236328125", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.34402847290039", "y": "229.8119354248047", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.853006362915039", "y": "229.37783813476562", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 428.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4712219238281", "y": "432.01580810546875", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.721435546875", "y": "435.5068664550781", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.97076416015625", "y": "425.0337219238281", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 410.82, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.47103881835938", "y": "406.9908752441406", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.74537658691406", "y": "403.50164794921875", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.92237854003906", "y": "413.9693298339844", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -506.72, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1669006347656", "y": "92.98015594482422", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.664794921875", "y": "92.85853576660156", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.1711120605469", "y": "93.223388671875", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -490.77, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.16552734375", "y": "245.8351593017578", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.66729736328125", "y": "245.72369384765625", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1619567871094", "y": "246.05809020996094", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 32.58, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3799743652344", "x": "173.4454803466797", "y": "35.77303695678711", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.38575744628906", "y": "39.272525787353516", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.56495666503906", "y": "28.774057388305664", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 30.78, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2735595703125", "x": "6.096487998962402", "y": "34.107757568359375", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.082276821136475", "y": "37.60772705078125", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.124910831451416", "y": "27.10781478881836", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 30.69, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61404418945312", "y": "33.7061882019043", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6187286376953", "y": "37.20618438720703", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6046600341797", "y": "26.706195831298828", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 29.93, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2468566894531", "y": "33.5247688293457", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.224365234375", "y": "37.024696350097656", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2918701171875", "y": "26.524913787841797", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 17.41, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.5028991699219", "y": "14.132526397705078", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.4099426269531", "y": "10.633761405944824", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.6888732910156", "y": "21.130056381225586", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 14.49, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3299560546875", "y": "10.977312088012695", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3896942138672", "y": "7.477822303771973", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.21047973632812", "y": "17.976293563842773", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 12.92, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575960159301758", "y": "9.462711334228516", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.561748504638672", "y": "5.962739944458008", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.60438346862793", "y": "16.46265411376953", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 12.51, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41551208496094", "y": "9.170232772827148", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41082763671875", "y": "5.670236110687256", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42489624023438", "y": "16.17022705078125", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "0", "x": 389.55, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "386.126953125", "y": "-235.0426788330078", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.62744140625", "y": "-234.98406982421875", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1259765625", "y": "-235.15989685058594", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 402.0, "y": -85.4, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "405.6141662597656", "y": "-85.36223602294922", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "409.1139831542969", "y": "-85.32567596435547", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6138000488281", "y": "-85.28910827636719", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 16.5, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575634002685547", "y": "12.962740898132324", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.56142234802246", "y": "9.462770462036133", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.547210693359375", "y": "5.962799072265625", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 16.9, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41432189941406", "y": "12.67023754119873", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4096221923828", "y": "9.17024040222168", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.40493774414062", "y": "5.670243740081787", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "0", "x": -6.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-9.628252983093262", "y": "-230.17373657226562", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-13.12211799621582", "y": "-230.38087463378906", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.615983963012695", "y": "-230.5880126953125", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-9.358698844909668", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.858672142028809", "y": "-75.68299865722656", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.358644485473633", "y": "-75.66926574707031", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-8.692384719848633", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.192340850830078", "y": "77.8146743774414", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692296028137207", "y": "77.83233642578125", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 4.69, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.12476921081543", "y": "-79.9434814453125", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "11.62474250793457", "y": "-79.95721435546875", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124715805053711", "y": "-79.970947265625", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.29, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.799537658691406", "y": "76.15229034423828", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "12.299492835998535", "y": "76.13462829589844", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79944896697998", "y": "76.1169662475586", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.19, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "9.344169616699219", "y": "229.6626434326172", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.841078758239746", "y": "229.80970764160156", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.337987899780273", "y": "229.95677185058594", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -494.19, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-490.6671142578125", "y": "245.83995056152344", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-487.1688232421875", "y": "245.7306671142578", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.6705322265625", "y": "245.6213836669922", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -503.22, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-506.6645202636719", "y": "92.97496795654297", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-510.1622009277344", "y": "92.84800720214844", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.659912109375", "y": "92.7210464477539", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 393.1, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "389.62744140625", "y": "-235.04331970214844", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "386.1278991699219", "y": "-234.98617553710938", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.6283874511719", "y": "-234.9290313720703", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 425.47, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.46160888671875", "y": "428.5073547363281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.71630859375", "y": "431.9980773925781", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.97100830078125", "y": "435.4888000488281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 414.14, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.45127868652344", "y": "410.49993896484375", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.72093200683594", "y": "407.0103454589844", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.99057006835938", "y": "403.520751953125", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.6, "y": 21.0, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.5164794921875", "y": "17.633331298828125", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.4296569824219", "y": "14.134408950805664", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.3428039550781", "y": "10.635486602783203", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 29.2, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3813171386719", "x": "173.4475555419922", "y": "32.272560119628906", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.3878173828125", "y": "35.77205276489258", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.32809448242188", "y": "39.271541595458984", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "2", "x": 326.5, "y": 20.8, "yaw": 180.0, "z": 1.7 } }, { "transform": { "pitch": "1.490559458732605", "x": "326.55828857421875", "y": "17.38355827331543", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6180114746094", "y": "13.88406753540039", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6777648925781", "y": "10.384577751159668", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 27.4, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2740478515625", "x": "6.096976280212402", "y": "30.607730865478516", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.082764625549316", "y": "34.10770034790039", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.068553447723389", "y": "37.60767364501953", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 27.31, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61387634277344", "y": "30.206186294555664", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6185760498047", "y": "33.70618438720703", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.62326049804688", "y": "37.206180572509766", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 26.55, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.24761962890625", "y": "30.024702072143555", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.22509765625", "y": "33.52463150024414", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.2026062011719", "y": "37.024559020996094", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 18.7, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.34207153320312", "y": "14.47802734375", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4018096923828", "y": "10.978536605834961", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4615478515625", "y": "7.479046821594238", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [], "scenario_type": "Scenario2" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": -333.24, "y": 435.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-332.98760986328125", "y": "432.04986572265625", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7461853027344", "y": "428.5581970214844", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.5047607421875", "y": "425.0665283203125", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 406.92, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.44630432128906", "y": "403.47784423828125", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.88621520996094", "y": "410.4554138183594", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.60617065429688", "y": "413.9441833496094", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 403.29, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-182.87094116210938", "y": "406.9427185058594", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.58535766601562", "y": "410.4310302734375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.29977416992188", "y": "413.91937255859375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -510.3, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-513.669189453125", "y": "92.98770141601562", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6730651855469", "y": "93.22088623046875", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17498779296875", "y": "93.33748626708984", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -514.1, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1750793457031", "y": "93.2253189086914", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6768493652344", "y": "93.33702087402344", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17864990234375", "y": "93.44872283935547", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -13.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-16.640460968017578", "y": "-230.1665802001953", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.651756286621094", "y": "-229.7690887451172", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.15740442276001", "y": "-229.57032775878906", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -487.27, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-483.66375732421875", "y": "245.8326873779297", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6600646972656", "y": "246.06027221679688", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1582336425781", "y": "246.17405700683594", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -483.59, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.15789794921875", "y": "246.0686798095703", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6559753417969", "y": "246.1850128173828", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1540222167969", "y": "246.30136108398438", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.69, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.133902549743652", "y": "-230.1801300048828", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.628005981445312", "y": "-230.38319396972656", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.145692825317383", "y": "-229.77401733398438", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 13.24, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "16.350406646728516", "y": "229.65643310546875", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.356184005737305", "y": "229.37210083007812", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.859072208404541", "y": "229.2299346923828", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.3, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624905586242676", "y": "-79.91557312011719", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.124932289123535", "y": "-79.90184020996094", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624959468841553", "y": "-79.88809967041016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.9, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": 16.8, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.859013557434082", "y": "229.3724365234375", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.361806869506836", "y": "229.2326202392578", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.864601135253906", "y": "229.09280395507812", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 432.39, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4604797363281", "y": "435.5253601074219", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.9693603515625", "y": "428.5426025390625", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7237854003906", "y": "425.0512390136719", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 36.18, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3785705566406", "x": "173.44720458984375", "y": "39.27357482910156", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.56666564941406", "y": "32.274593353271484", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.62640380859375", "y": "28.775104522705078", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 34.38, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2730407714844", "x": "6.096894264221191", "y": "37.6077880859375", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.125317096710205", "y": "30.607847213745117", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.139528274536133", "y": "27.10787582397461", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 34.29, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6138916015625", "y": "37.20619201660156", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60450744628906", "y": "30.206199645996094", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.59982299804688", "y": "26.70620346069336", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 33.53, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.24749755859375", "y": "37.024845123291016", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.2925109863281", "y": "30.02499008178711", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.31500244140625", "y": "26.525062561035156", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 39.53, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.37725830078125", "x": "173.5640869140625", "y": "35.775062561035156", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.6238250732422", "y": "32.275569915771484", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.68356323242188", "y": "28.776081085205078", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 37.73, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2725524902344", "x": "6.124706745147705", "y": "34.107872009277344", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.138918399810791", "y": "30.60790252685547", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.153129577636719", "y": "27.10793113708496", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 37.64, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60472106933594", "y": "33.70620346069336", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6000213623047", "y": "30.206205368041992", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.5953369140625", "y": "26.706209182739258", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 36.88, "yaw": 359.0, "z": 1.13 } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.2915344238281", "y": "33.52505874633789", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3140563964844", "y": "30.025129318237305", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3365478515625", "y": "26.52520179748535", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "0", "x": -12.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.358753204345703", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358806610107422", "y": "-75.72421264648438", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.8588337898254395", "y": "-75.73794555664062", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 14.1, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.49053955078125", "y": "10.631532669067383", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.69122314453125", "y": "17.62865447998047", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.79156494140625", "y": "21.127216339111328", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 11.9, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.3455047607422", "y": "7.477066993713379", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.2260284423828", "y": "14.47604751586914", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.16629028320312", "y": "17.97553825378418", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 9.52, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.603975296020508", "y": "12.962626457214355", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618186950683594", "y": "16.46259880065918", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 9.11, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41539001464844", "y": "5.670230388641357", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42477416992188", "y": "12.6702241897583", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42945861816406", "y": "16.17022132873535", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 10.45, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.70556640625", "y": "14.126648902893066", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.8155212402344", "y": "17.624921798706055", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.92547607421875", "y": "21.123193740844727", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 7.53, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.215087652206421", "x": "156.21119689941406", "y": "10.975284576416016", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.15145874023438", "y": "14.474775314331055", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.0917205810547", "y": "17.974266052246094", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 5.96, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.604219436645508", "y": "9.462596893310547", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618431091308594", "y": "12.962567329406738", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.63264274597168", "y": "16.462539672851562", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 5.55, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4248504638672", "y": "9.170221328735352", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42955017089844", "y": "12.670218467712402", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.43423461914062", "y": "16.170215606689453", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "0", "x": 385.91, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "382.6264343261719", "y": "-235.0435333251953", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "389.6253967285156", "y": "-235.16390991210938", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1248779296875", "y": "-235.22410583496094", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 409.22, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "412.61456298828125", "y": "-85.36454010009766", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61492919921875", "y": "-85.43766784667969", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1151123046875", "y": "-85.47423553466797", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-15.692474365234375", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.6925630569458", "y": "77.76168823242188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192607879638672", "y": "77.74402618408203", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 412.59, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1151123046875", "y": "-85.43630981445312", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61529541015625", "y": "-85.47286987304688", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.115478515625", "y": "-85.50943756103516", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.97, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.157381057739258", "y": "-229.76759338378906", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.662800788879395", "y": "-229.57290649414062", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.168219089508057", "y": "-229.3782196044922", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.59, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858835220336914", "y": "-75.72463989257812", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358861923217773", "y": "-75.7383804321289", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858889102935791", "y": "-75.75211334228516", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.94, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192610740661621", "y": "77.7610855102539", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.692655563354492", "y": "77.74342346191406", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192700386047363", "y": "77.72576141357422", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 11.74, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.124823570251465", "y": "-79.94327545166016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.1248779296875", "y": "-79.91580963134766", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624904632568359", "y": "-79.90206909179688", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 12.33, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.799628257751465", "y": "76.15249633789062", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.79971694946289", "y": "76.18782043457031", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.299761772155762", "y": "76.20548248291016", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 405.54, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1143493652344", "y": "-85.36266326904297", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6141662597656", "y": "-85.32609558105469", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1147155761719", "y": "-85.435791015625", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.31, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858723640441895", "y": "-75.6960678100586", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.35869598388672", "y": "-75.68233489990234", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858777046203613", "y": "-75.72354125976562", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -8.66, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192425727844238", "y": "77.79782104492188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692380905151367", "y": "77.81548309326172", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192514896392822", "y": "77.76249694824219", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.4, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624799728393555", "y": "-79.9426498413086", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124772071838379", "y": "-79.95638275146484", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624853134155273", "y": "-79.91517639160156", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.63, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "12.299577713012695", "y": "76.15148162841797", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79953384399414", "y": "76.13381958007812", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.2996673583984375", "y": "76.18680572509766", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.53, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.847021102905273", "y": "229.667236328125", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.34402847290039", "y": "229.8119354248047", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.853006362915039", "y": "229.37783813476562", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 428.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4712219238281", "y": "432.01580810546875", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.721435546875", "y": "435.5068664550781", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.97076416015625", "y": "425.0337219238281", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 410.82, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.47103881835938", "y": "406.9908752441406", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.74537658691406", "y": "403.50164794921875", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.92237854003906", "y": "413.9693298339844", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -506.72, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1669006347656", "y": "92.98015594482422", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.664794921875", "y": "92.85853576660156", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.1711120605469", "y": "93.223388671875", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -490.77, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.16552734375", "y": "245.8351593017578", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.66729736328125", "y": "245.72369384765625", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1619567871094", "y": "246.05809020996094", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 32.58, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3799743652344", "x": "173.4454803466797", "y": "35.77303695678711", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.38575744628906", "y": "39.272525787353516", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.56495666503906", "y": "28.774057388305664", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 30.78, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2735595703125", "x": "6.096487998962402", "y": "34.107757568359375", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.082276821136475", "y": "37.60772705078125", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.124910831451416", "y": "27.10781478881836", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 30.69, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61404418945312", "y": "33.7061882019043", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6187286376953", "y": "37.20618438720703", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6046600341797", "y": "26.706195831298828", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 29.93, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2468566894531", "y": "33.5247688293457", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.224365234375", "y": "37.024696350097656", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2918701171875", "y": "26.524913787841797", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 17.41, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.5028991699219", "y": "14.132526397705078", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.4099426269531", "y": "10.633761405944824", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.6888732910156", "y": "21.130056381225586", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 14.49, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3299560546875", "y": "10.977312088012695", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3896942138672", "y": "7.477822303771973", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.21047973632812", "y": "17.976293563842773", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 12.92, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575960159301758", "y": "9.462711334228516", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.561748504638672", "y": "5.962739944458008", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.60438346862793", "y": "16.46265411376953", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 12.51, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41551208496094", "y": "9.170232772827148", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41082763671875", "y": "5.670236110687256", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42489624023438", "y": "16.17022705078125", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "0", "x": 389.55, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "386.126953125", "y": "-235.0426788330078", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.62744140625", "y": "-234.98406982421875", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1259765625", "y": "-235.15989685058594", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 402.0, "y": -85.4, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "405.6141662597656", "y": "-85.36223602294922", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "409.1139831542969", "y": "-85.32567596435547", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6138000488281", "y": "-85.28910827636719", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 16.5, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575634002685547", "y": "12.962740898132324", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.56142234802246", "y": "9.462770462036133", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.547210693359375", "y": "5.962799072265625", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 16.9, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41432189941406", "y": "12.67023754119873", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4096221923828", "y": "9.17024040222168", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.40493774414062", "y": "5.670243740081787", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "0", "x": -6.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-9.628252983093262", "y": "-230.17373657226562", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-13.12211799621582", "y": "-230.38087463378906", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.615983963012695", "y": "-230.5880126953125", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-9.358698844909668", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.858672142028809", "y": "-75.68299865722656", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.358644485473633", "y": "-75.66926574707031", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-8.692384719848633", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.192340850830078", "y": "77.8146743774414", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692296028137207", "y": "77.83233642578125", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 4.69, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.12476921081543", "y": "-79.9434814453125", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "11.62474250793457", "y": "-79.95721435546875", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124715805053711", "y": "-79.970947265625", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.29, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.799537658691406", "y": "76.15229034423828", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "12.299492835998535", "y": "76.13462829589844", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79944896697998", "y": "76.1169662475586", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.19, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "9.344169616699219", "y": "229.6626434326172", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.841078758239746", "y": "229.80970764160156", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.337987899780273", "y": "229.95677185058594", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -494.19, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-490.6671142578125", "y": "245.83995056152344", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-487.1688232421875", "y": "245.7306671142578", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.6705322265625", "y": "245.6213836669922", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -503.22, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-506.6645202636719", "y": "92.97496795654297", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-510.1622009277344", "y": "92.84800720214844", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.659912109375", "y": "92.7210464477539", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 393.1, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "389.62744140625", "y": "-235.04331970214844", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "386.1278991699219", "y": "-234.98617553710938", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.6283874511719", "y": "-234.9290313720703", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 425.47, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.46160888671875", "y": "428.5073547363281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.71630859375", "y": "431.9980773925781", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.97100830078125", "y": "435.4888000488281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 414.14, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.45127868652344", "y": "410.49993896484375", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.72093200683594", "y": "407.0103454589844", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.99057006835938", "y": "403.520751953125", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.6, "y": 21.0, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.5164794921875", "y": "17.633331298828125", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.4296569824219", "y": "14.134408950805664", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.3428039550781", "y": "10.635486602783203", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 29.2, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3813171386719", "x": "173.4475555419922", "y": "32.272560119628906", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.3878173828125", "y": "35.77205276489258", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.32809448242188", "y": "39.271541595458984", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "2", "x": 326.5, "y": 20.8, "yaw": 180.0, "z": 1.7 } }, { "transform": { "pitch": "1.490559458732605", "x": "326.55828857421875", "y": "17.38355827331543", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6180114746094", "y": "13.88406753540039", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6777648925781", "y": "10.384577751159668", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 27.4, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2740478515625", "x": "6.096976280212402", "y": "30.607730865478516", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.082764625549316", "y": "34.10770034790039", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.068553447723389", "y": "37.60767364501953", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 27.31, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61387634277344", "y": "30.206186294555664", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6185760498047", "y": "33.70618438720703", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.62326049804688", "y": "37.206180572509766", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 26.55, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.24761962890625", "y": "30.024702072143555", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.22509765625", "y": "33.52463150024414", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.2026062011719", "y": "37.024559020996094", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 18.7, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.34207153320312", "y": "14.47802734375", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4018096923828", "y": "10.978536605834961", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4615478515625", "y": "7.479046821594238", "yaw": "-179.02207946777344", "z": "9.125747680664062" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.33", "y": "-173.27", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "131.66", "y": "-209.1", "yaw": "98.778381", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.92", "y": "-173.39", "yaw": "179.198364", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "92.80", "y": "-170.10", "yaw": "0.12323", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.46", "y": "-170.8", "yaw": "0.453278", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "131.23", "y": "-209.9", "yaw": "98.115265", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "97.61", "y": "-173.41", "yaw": "180.754196", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "58.96", "y": "-208.40", "yaw": "90.754181", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "25.89", "y": "-170.29", "yaw": "1.018799", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "58.81", "y": "-207.71", "yaw": "91.018799", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "97.53", "y": "-173.20", "yaw": "180.886658", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "26.30", "y": "-170.13", "yaw": "0.886627", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "293.32", "y": "-309.45", "yaw": "183.428238", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "259.15", "y": "-271.67", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "221.55", "y": "-307.81", "yaw": "0.056519", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "293.68", "y": "-310.23", "yaw": "182.596146", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "221.79", "y": "-307.84", "yaw": "359.213013", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.92", "y": "-271.79", "yaw": "271.056641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "291.60", "y": "-249.86", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "254.99", "y": "-283.71", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "258.30", "y": "-211.0", "yaw": "272.521973", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.61", "y": "-211.72", "yaw": "270.699127", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "291.96", "y": "-250.4", "yaw": "178.90509", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "220.54", "y": "-246.26", "yaw": "0.699097", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "219.52", "y": "-246.20", "yaw": "0.076721", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.58", "y": "-212.43", "yaw": "270.076752", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "255.6", "y": "-283.25", "yaw": "90.076691", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.8", "y": "-284.50", "yaw": "89.832275", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "220.22", "y": "-246.15", "yaw": "359.832275", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "292.3", "y": "-250.30", "yaw": "179.832275", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.26", "y": "-122.5", "yaw": "180.000015", "z": "1.2" } ], "left": [ { "pitch": "0.0", "x": "254.73", "y": "-154.69", "yaw": "90.0", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "292.83", "y": "-122.44", "yaw": "180.13298", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "221.82", "y": "-120.78", "yaw": "5.250366", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "222.29", "y": "-120.16", "yaw": "1.962585", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "254.68", "y": "-154.78", "yaw": "91.962524", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.99", "y": "9.30", "yaw": "180.317535", "z": "1.0" }, { "pitch": "0.0", "x": "-337.66", "y": "5.69", "yaw": "180.196899", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.5", "y": "16.36", "yaw": "181.84436", "z": "1.0" }, { "pitch": "0.0", "x": "-337.5", "y": "13.9", "yaw": "181.019409", "z": "1.0" }, { "pitch": "0.0", "x": "-336.71", "y": "9.43", "yaw": "180.933701", "z": "1.0" }, { "pitch": "0.0", "x": "-336.38", "y": "5.83", "yaw": "180.079086", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "206.97", "y": "-140.26", "yaw": "257.906311", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "235.73", "y": "-172.75", "yaw": "180.923157", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "166.89", "y": "-169.88", "yaw": "0.923157", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "235.41", "y": "-173.11", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "198.98", "y": "-204.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "205.92", "y": "-142.19", "yaw": "259.577576", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "199.6", "y": "-204.6", "yaw": "91.002838", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "165.6", "y": "-169.56", "yaw": "0.059082", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "235.86", "y": "-173.64", "yaw": "177.911682", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.55", "y": "-169.68", "yaw": "0.490326", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "207.25", "y": "-139.94", "yaw": "258.321381", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "199.18", "y": "-204.78", "yaw": "90.490295", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [], "scenario_type": "Scenario5" }, { "available_event_configurations": [], "scenario_type": "Scenario6" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.33", "y": "-173.27", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "131.66", "y": "-209.1", "yaw": "98.778381", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.92", "y": "-173.39", "yaw": "179.198364", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "92.80", "y": "-170.10", "yaw": "0.12323", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.46", "y": "-170.8", "yaw": "0.453278", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "131.23", "y": "-209.9", "yaw": "98.115265", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "97.61", "y": "-173.41", "yaw": "180.754196", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "58.96", "y": "-208.40", "yaw": "90.754181", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "25.89", "y": "-170.29", "yaw": "1.018799", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "58.81", "y": "-207.71", "yaw": "91.018799", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "97.53", "y": "-173.20", "yaw": "180.886658", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "26.30", "y": "-170.13", "yaw": "0.886627", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "293.32", "y": "-309.45", "yaw": "183.428238", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "259.15", "y": "-271.67", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "221.55", "y": "-307.81", "yaw": "0.056519", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "293.68", "y": "-310.23", "yaw": "182.596146", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "221.79", "y": "-307.84", "yaw": "359.213013", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.92", "y": "-271.79", "yaw": "271.056641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "291.60", "y": "-249.86", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "254.99", "y": "-283.71", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "258.30", "y": "-211.0", "yaw": "272.521973", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.61", "y": "-211.72", "yaw": "270.699127", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "291.96", "y": "-250.4", "yaw": "178.90509", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "220.54", "y": "-246.26", "yaw": "0.699097", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "219.52", "y": "-246.20", "yaw": "0.076721", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.58", "y": "-212.43", "yaw": "270.076752", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "255.6", "y": "-283.25", "yaw": "90.076691", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.8", "y": "-284.50", "yaw": "89.832275", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "220.22", "y": "-246.15", "yaw": "359.832275", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "292.3", "y": "-250.30", "yaw": "179.832275", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.26", "y": "-122.5", "yaw": "180.000015", "z": "1.2" } ], "left": [ { "pitch": "0.0", "x": "254.73", "y": "-154.69", "yaw": "90.0", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "292.83", "y": "-122.44", "yaw": "180.13298", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "221.82", "y": "-120.78", "yaw": "5.250366", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "222.29", "y": "-120.16", "yaw": "1.962585", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "254.68", "y": "-154.78", "yaw": "91.962524", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.53", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.99", "y": "9.30", "yaw": "180.317535", "z": "1.0" }, { "pitch": "0.0", "x": "-337.66", "y": "5.69", "yaw": "180.196899", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.6", "y": "-18.77", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.32", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-380.7", "y": "-19.22", "yaw": "92.245758", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.53", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.8", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.76", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-20.12", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.99", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.84", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-379.96", "y": "-18.98", "yaw": "90.454224", "z": "1.0" }, { "pitch": "0.0", "x": "-383.45", "y": "-19.87", "yaw": "90.454224", "z": "1.0" } ] }, "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.5", "y": "16.36", "yaw": "181.84436", "z": "1.0" }, { "pitch": "0.0", "x": "-337.5", "y": "13.9", "yaw": "181.019409", "z": "1.0" }, { "pitch": "0.0", "x": "-336.71", "y": "9.43", "yaw": "180.933701", "z": "1.0" }, { "pitch": "0.0", "x": "-336.38", "y": "5.83", "yaw": "180.079086", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "206.97", "y": "-140.26", "yaw": "257.906311", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "235.73", "y": "-172.75", "yaw": "180.923157", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "166.89", "y": "-169.88", "yaw": "0.923157", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "235.41", "y": "-173.11", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "198.98", "y": "-204.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "205.92", "y": "-142.19", "yaw": "259.577576", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "199.6", "y": "-204.6", "yaw": "91.002838", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "165.6", "y": "-169.56", "yaw": "0.059082", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "235.86", "y": "-173.64", "yaw": "177.911682", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.55", "y": "-169.68", "yaw": "0.490326", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "207.25", "y": "-139.94", "yaw": "258.321381", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "199.18", "y": "-204.78", "yaw": "90.490295", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.33", "y": "-173.27", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "131.66", "y": "-209.1", "yaw": "98.778381", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "97.61", "y": "-173.41", "yaw": "180.754196", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "58.96", "y": "-208.40", "yaw": "90.754181", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "221.79", "y": "-307.84", "yaw": "359.213013", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.92", "y": "-271.79", "yaw": "271.056641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.26", "y": "-122.5", "yaw": "180.000015", "z": "1.2" } ], "left": [ { "pitch": "0.0", "x": "254.73", "y": "-154.69", "yaw": "90.0", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.92", "y": "-173.39", "yaw": "179.198364", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "92.80", "y": "-170.10", "yaw": "0.12323", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.46", "y": "-170.8", "yaw": "0.453278", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "131.23", "y": "-209.9", "yaw": "98.115265", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "25.89", "y": "-170.29", "yaw": "1.018799", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "58.81", "y": "-207.71", "yaw": "91.018799", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "97.53", "y": "-173.20", "yaw": "180.886658", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "26.30", "y": "-170.13", "yaw": "0.886627", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.26", "y": "-311.19", "yaw": "180.000015", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "202.68", "y": "-346.16", "yaw": "90.0", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "204.30", "y": "-272.12", "yaw": "272.176117", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "204.53", "y": "-271.36", "yaw": "270.697601", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "239.0", "y": "-310.81", "yaw": "180.697571", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "165.98", "y": "-307.85", "yaw": "0.697571", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.43", "y": "-307.91", "yaw": "359.881195", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "204.4", "y": "-271.52", "yaw": "272.443604", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "202.57", "y": "-347.6", "yaw": "92.279572", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "202.60", "y": "-346.95", "yaw": "91.150391", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "166.35", "y": "-307.83", "yaw": "1.150391", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "239.26", "y": "-310.71", "yaw": "181.150391", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "238.26", "y": "-249.59", "yaw": "179.159729", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "201.0", "y": "-282.47", "yaw": "91.26181", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "203.27", "y": "-210.65", "yaw": "271.428406", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "203.7", "y": "-210.76", "yaw": "270.354645", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "237.5", "y": "-249.58", "yaw": "180.35463", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "168.42", "y": "-240.25", "yaw": "350.167725", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "167.64", "y": "-240.73", "yaw": "350.624207", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "203.14", "y": "-210.77", "yaw": "270.838318", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "201.11", "y": "-282.78", "yaw": "89.17395", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "201.10", "y": "-282.79", "yaw": "91.760925", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "167.84", "y": "-240.47", "yaw": "349.147614", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "238.2", "y": "-249.68", "yaw": "179.019775", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "293.32", "y": "-309.45", "yaw": "183.428238", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "259.15", "y": "-271.67", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "221.55", "y": "-307.81", "yaw": "0.056519", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "293.68", "y": "-310.23", "yaw": "182.596146", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "292.54", "y": "-172.71", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "254.86", "y": "-207.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "258.51", "y": "-133.24", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.17", "y": "-133.36", "yaw": "270.132416", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "292.35", "y": "-172.85", "yaw": "180.132401", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "218.74", "y": "-169.11", "yaw": "0.132385", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "218.37", "y": "-169.66", "yaw": "359.321442", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "257.87", "y": "-133.6", "yaw": "270.162109", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "254.47", "y": "-207.29", "yaw": "89.321411", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.18", "y": "-206.62", "yaw": "89.264893", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "218.62", "y": "-169.15", "yaw": "359.264893", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "292.46", "y": "-173.45", "yaw": "179.264893", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "292.83", "y": "-122.44", "yaw": "180.13298", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "221.82", "y": "-120.78", "yaw": "5.250366", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "222.29", "y": "-120.16", "yaw": "1.962585", "z": "1.2" } ], "right": [ { "pitch": "0.0", "x": "254.68", "y": "-154.78", "yaw": "91.962524", "z": "1.2" } ] }, "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "345.91", "y": "-248.90", "yaw": "182.979889", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "310.10", "y": "-281.95", "yaw": "84.92395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "314.91", "y": "-213.31", "yaw": "269.926514", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "314.78", "y": "-213.6", "yaw": "270.509521", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "346.19", "y": "-248.37", "yaw": "183.987366", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "278.33", "y": "-245.67", "yaw": "0.509491", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "278.54", "y": "-246.21", "yaw": "358.94519", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "314.80", "y": "-213.10", "yaw": "270.659332", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "309.62", "y": "-282.34", "yaw": "86.300964", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.27", "y": "-282.38", "yaw": "86.872681", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "315.17", "y": "-218.24", "yaw": "270.413025", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "346.1", "y": "-248.73", "yaw": "185.231613", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.44", "y": "-172.62", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-205.80", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "314.39", "y": "-135.73", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.85", "y": "-135.34", "yaw": "271.263733", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "341.43", "y": "-172.19", "yaw": "181.263718", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "277.51", "y": "-169.20", "yaw": "1.263702", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "277.37", "y": "-169.46", "yaw": "0.831573", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "314.25", "y": "-135.2", "yaw": "270.831573", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "311.1", "y": "-206.75", "yaw": "90.831543", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "311.13", "y": "-205.89", "yaw": "90.423126", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "277.78", "y": "-169.20", "yaw": "0.423126", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "341.64", "y": "-172.22", "yaw": "180.423126", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "343.12", "y": "-122.82", "yaw": "174.794922", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "310.97", "y": "-154.72", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "313.91", "y": "-84.85", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "313.88", "y": "-84.89", "yaw": "270.13266", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "343.8", "y": "-122.81", "yaw": "174.972046", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "275.63", "y": "-118.66", "yaw": "2.654602", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "275.96", "y": "-118.30", "yaw": "0.453278", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "314.23", "y": "-84.44", "yaw": "270.453278", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "310.85", "y": "-154.39", "yaw": "90.453247", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "310.97", "y": "-154.66", "yaw": "90.773285", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "275.16", "y": "-118.64", "yaw": "0.773285", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "343.0", "y": "-123.31", "yaw": "174.528503", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "379.46", "y": "-172.54", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "349.7", "y": "-205.61", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "351.54", "y": "-131.60", "yaw": "270.0", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "352.7", "y": "-132.8", "yaw": "270.321075", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "380.62", "y": "-172.21", "yaw": "180.321075", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "316.48", "y": "-168.47", "yaw": "0.321045", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "348.89", "y": "-205.68", "yaw": "91.151917", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "316.9", "y": "-168.89", "yaw": "1.151917", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "379.82", "y": "-172.42", "yaw": "181.151901", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "316.67", "y": "-168.97", "yaw": "0.832764", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "351.54", "y": "-131.71", "yaw": "270.832764", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "349.0", "y": "-204.54", "yaw": "90.832703", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-337.99", "y": "9.30", "yaw": "180.317535", "z": "1.0" }, { "pitch": "0.0", "x": "-337.66", "y": "5.69", "yaw": "180.196899", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "291.60", "y": "-249.86", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "254.99", "y": "-283.71", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "258.30", "y": "-211.0", "yaw": "272.521973", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "258.61", "y": "-211.72", "yaw": "270.699127", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "291.96", "y": "-250.4", "yaw": "178.90509", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "220.54", "y": "-246.26", "yaw": "0.699097", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "219.52", "y": "-246.20", "yaw": "0.076721", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "258.58", "y": "-212.43", "yaw": "270.076752", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "255.6", "y": "-283.25", "yaw": "90.076691", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "255.8", "y": "-284.50", "yaw": "89.832275", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "220.22", "y": "-246.15", "yaw": "359.832275", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "292.3", "y": "-250.30", "yaw": "179.832275", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "206.97", "y": "-140.26", "yaw": "257.906311", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "235.73", "y": "-172.75", "yaw": "180.923157", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "166.89", "y": "-169.88", "yaw": "0.923157", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "235.41", "y": "-173.11", "yaw": "180.000015", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "198.98", "y": "-204.57", "yaw": "90.0", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "205.92", "y": "-142.19", "yaw": "259.577576", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "199.6", "y": "-204.6", "yaw": "91.002838", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "165.6", "y": "-169.56", "yaw": "0.059082", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "235.86", "y": "-173.64", "yaw": "177.911682", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.55", "y": "-169.68", "yaw": "0.490326", "z": "1.19" } ], "left": [ { "pitch": "0.0", "x": "207.25", "y": "-139.94", "yaw": "258.321381", "z": "1.19" } ], "right": [ { "pitch": "0.0", "x": "199.18", "y": "-204.78", "yaw": "90.490295", "z": "1.19" } ] }, "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario10" } ], "Town05": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.73, "y": 145.88, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 55.87, "y": -145.22, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 101.5, "y": 137.98, "yaw": 164.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.81, "y": 142.49, "yaw": 344.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 136.31, "y": 121.37, "yaw": 137.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 137.75, "y": 125.7, "yaw": 317.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 149.54, "y": 101.12, "yaw": 107.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 152.94, "y": 104.16, "yaw": 287.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": 49.67, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": 51.39, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.37, "y": 16.76, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.55, "y": -16.99, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": -59.22, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": -57.49, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 150.46, "y": -102.24, "yaw": 76.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 154.95, "y": -101.44, "yaw": 255.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 134.58, "y": -127.97, "yaw": 46.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 138.88, "y": -129.5, "yaw": 225.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 98.27, "y": -141.73, "yaw": 11.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.88, "y": -145.47, "yaw": 190.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0", "x": -240.52, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.52142333984375", "y": "-76.91566467285156", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.5221405029297", "y": "-76.96470642089844", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.39, "y": 201.6, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-124.4139175415039", "y": "34.73600387573242", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [], "scenario_type": "Scenario2" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.6", "y": "29.6", "yaw": "268.398804", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "120.28", "y": "2.26", "yaw": "358.398743", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "151.62", "y": "-30.72", "yaw": "88.888824", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "120.37", "y": "2.29", "yaw": "358.888824", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "151.22", "y": "-30.42", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "155.36", "y": "29.78", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [], "scenario_type": "Scenario5" }, { "available_event_configurations": [], "scenario_type": "Scenario6" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.6", "y": "29.6", "yaw": "268.398804", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "120.28", "y": "2.26", "yaw": "358.398743", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "202.40", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.22", "y": "154.61", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "202.40", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.22", "y": "154.61", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "202.40", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.22", "y": "154.61", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.55", "y": "202.25", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.5", "y": "155.19", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.55", "y": "202.25", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.5", "y": "155.19", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.55", "y": "202.25", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.5", "y": "155.19", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "151.62", "y": "-30.72", "yaw": "88.888824", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "120.37", "y": "2.29", "yaw": "358.888824", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.20", "y": "-200.72", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.18", "y": "-151.85", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.20", "y": "-200.72", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.18", "y": "-151.85", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.20", "y": "-200.72", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.18", "y": "-151.85", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "-200.77", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.53", "y": "-152.61", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "-200.77", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.53", "y": "-152.61", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "-200.77", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "35.53", "y": "-152.61", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "151.22", "y": "-30.42", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "155.36", "y": "29.78", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-124.4139175415039", "y": "34.73600387573242", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } } ], "scenario_type": "Scenario10" } ], "Town06": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 669.39, "y": 83.38, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "672.7225952148438", "y": "83.4161376953125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7229614257812", "y": "83.34022521972656", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2232055664062", "y": "83.30226135253906", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.723388671875", "y": "83.2643051147461", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.7, "y": 83.5, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.2218627929688", "y": "83.46227264404297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7220458984375", "y": "83.42431640625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2222900390625", "y": "83.3863525390625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7224731445312", "y": "83.34839630126953", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.3, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-8.675992965698242", "y": "-53.622528076171875", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.0, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.176236152648926", "y": "-53.574485778808594", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 2.4, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.828932285308838", "y": "20.622880935668945", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.9, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.3291661739349365", "y": "20.576173782348633", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -16.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-20.065515518188477", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.5749969482422", "y": "-23.56549072265625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-13.065561294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -20.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-23.56553840637207", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-16.565584182739258", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6259765625", "y": "-13.065608024597168", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -23.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.6136016845703", "y": "-20.065608978271484", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.62635803222656", "y": "-16.565631866455078", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.63909912109375", "y": "-13.065655708312988", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -12.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187618255615234", "y": "-16.09782600402832", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.174869537353516", "y": "-19.597803115844727", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -16.1, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187252044677734", "y": "-19.597848892211914", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.212745666503906", "y": "-12.597894668579102", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.91, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.90859985351562", "y": "45.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9071807861328", "y": "48.9715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.90577697753906", "y": "52.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.92, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.91854858398438", "y": "48.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.91714477539062", "y": "52.47157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.92138671875", "y": "41.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9285888671875", "y": "52.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93141174316406", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93283081054688", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 52.88, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9315643310547", "y": "48.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9329833984375", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9344024658203", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -19.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.21311569213867", "y": "-16.097919464111328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.225860595703125", "y": "-12.597942352294922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 658.6, "y": 82.95, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "662.2265625", "y": "82.98932647705078", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.726318359375", "y": "83.02729034423828", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2261352539062", "y": "83.06524658203125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7259521484375", "y": "83.10320281982422", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 662.3, "y": 83.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "665.7197265625", "y": "83.63709259033203", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2195434570312", "y": "83.675048828125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7193603515625", "y": "83.71300506591797", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7201538085938", "y": "83.56117248535156", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.8, "y": 83.17, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.224609375", "y": "83.20713806152344", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7244262695312", "y": "83.2450942993164", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2250366210938", "y": "83.13121795654297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7252197265625", "y": "83.09326171875", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.4, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "12.778694152832031", "y": "276.646728515625", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.77956485748291", "y": "276.75714111328125", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 239.9, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.6988410949707", "y": "243.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68668746948242", "y": "246.61331176757812", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.674537658691406", "y": "250.11329650878906", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -10.2, "y": 213.5, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.720656394958496", "y": "213.4451141357422", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2210917472839355", "y": "213.38990783691406", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6298828125", "y": "138.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6454467773438", "y": "138.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 657.7, "y": 183.15, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "661.1398315429688", "y": "183.1873016357422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6395874023438", "y": "183.2252655029297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.139404296875", "y": "183.2632293701172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6392211914062", "y": "183.30117797851562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 661.7, "y": 183.26, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "664.6388549804688", "y": "183.2918701171875", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.138671875", "y": "183.329833984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6384887695312", "y": "183.36778259277344", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6392822265625", "y": "183.21595764160156", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.658935546875", "y": "138.49703979492188", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.2, "y": 183.37, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.137939453125", "y": "183.40187072753906", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6377563476562", "y": "183.4398193359375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1383666992188", "y": "183.32594299316406", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6385498046875", "y": "183.28799438476562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 668.99, "y": 183.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "671.6359252929688", "y": "183.60870361328125", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6362915039062", "y": "183.5327911376953", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1365356445312", "y": "183.4948272705078", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.63671875", "y": "183.45687866210938", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.3, "y": 183.7, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.1351928710938", "y": "183.6548309326172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6353759765625", "y": "183.6168670654297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1356201171875", "y": "183.5789031982422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6358032226562", "y": "183.54095458984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -13.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58847045898438", "y": "-16.565494537353516", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.57571411132812", "y": "-20.065471649169922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.56297302246094", "y": "-23.565448760986328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.278183937072754", "y": "276.6419982910156", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.777749061584473", "y": "276.5867919921875", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3915710449219", "y": "45.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3932800292969", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39495849609375", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3915100097656", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3931884765625", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3880920410156", "y": "41.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3863830566406", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39154052734375", "y": "52.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "45.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3864440917969", "y": "41.744102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3847351074219", "y": "38.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 52.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.27813720703125", "y": "48.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27642822265625", "y": "45.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27471923828125", "y": "41.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27301025390625", "y": "38.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.4, "y": 138.59, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.39260864257812", "y": "135.4395294189453", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.49070739746094", "y": "138.93931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.48249816894531", "y": "135.43931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -239.6, "y": 240.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-239.59410095214844", "y": "243.68092346191406", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58779907226562", "y": "247.180908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58151245117188", "y": "250.680908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -359.5, "y": 58.1, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-362.68389892578125", "y": "57.73311233520508", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-366.160888671875", "y": "57.33245086669922", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.63787841796875", "y": "56.931793212890625", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -13.9, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.298583984375", "y": "-17.034290313720703", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28582763671875", "y": "-20.53426742553711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.2731018066406", "y": "-24.034242630004883", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 503.51, "y": -10.4, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "503.5177307128906", "y": "-13.939313888549805", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5253601074219", "y": "-17.439306259155273", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.53302001953125", "y": "-20.93929672241211", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5406494140625", "y": "-24.439289093017578", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 38.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.401611328125", "y": "41.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.405029296875", "y": "48.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4067077636719", "y": "52.24409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 38.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.40155029296875", "y": "41.81858444213867", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40325927734375", "y": "45.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40496826171875", "y": "48.818580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40667724609375", "y": "52.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 41.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29331970214844", "y": "45.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29661560058594", "y": "48.73708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29991149902344", "y": "52.23708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 138.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3869323730469", "y": "141.3854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3725891113281", "y": "144.8854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3582458496094", "y": "148.38539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3439025878906", "y": "151.88536071777344", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 137.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3870544433594", "y": "140.75856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3727111816406", "y": "144.25852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3583679199219", "y": "147.7584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3440246582031", "y": "151.2584686279297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.3, "y": 136.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "140.13125610351562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2720184326172", "y": "143.6312255859375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.25767517089844", "y": "147.13119506835938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2433319091797", "y": "150.63116455078125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.1, "y": 135.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 333.2, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1989440917969", "y": "241.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.19775390625", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.196533203125", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1953430175781", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89891052246094", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89772033691406", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8965301513672", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8953399658203", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 238.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09896469116211", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09777069091797", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.096576690673828", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.095382690429688", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [], "scenario_type": "Scenario2" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [], "scenario_type": "Scenario5" }, { "available_event_configurations": [], "scenario_type": "Scenario6" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 669.39, "y": 83.38, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7225952148438", "y": "83.4161376953125", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.7229614257812", "y": "83.34022521972656", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2232055664062", "y": "83.30226135253906", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.19", "y": "52.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.20", "y": "48.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.21", "y": "45.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.22", "y": "41.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.23", "y": "38.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.723388671875", "y": "83.2643051147461", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 672.7, "y": 83.5, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.2218627929688", "y": "83.46227264404297", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.7220458984375", "y": "83.42431640625", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2222900390625", "y": "83.3863525390625", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.29", "y": "52.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.30", "y": "48.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.31", "y": "45.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.32", "y": "41.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.33", "y": "38.34", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.7224731445312", "y": "83.34839630126953", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "48.99", "y": "-12.63", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.2", "y": "-16.23", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.4", "y": "-19.73", "yaw": "180.396667", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.3, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "48.99", "y": "-12.63", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.2", "y": "-16.23", "yaw": "180.396667", "z": "1.0" }, { "pitch": "0.0", "x": "49.4", "y": "-19.73", "yaw": "180.396667", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-8.675992965698242", "y": "-53.622528076171875", "yaw": "90.3823013305664", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.40", "y": "-12.63", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.47", "y": "-16.13", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.48", "y": "-19.63", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.4, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.40", "y": "-12.63", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.47", "y": "-16.13", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.48", "y": "-19.63", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.828932285308838", "y": "20.622880935668945", "yaw": "270.3822937011719", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.32", "y": "-12.69", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.46", "y": "-16.19", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.52", "y": "-19.69", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.9, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "48.32", "y": "-12.69", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.46", "y": "-16.19", "yaw": "180.965454", "z": "1.0" }, { "pitch": "0.0", "x": "48.52", "y": "-19.69", "yaw": "180.965454", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.3291661739349365", "y": "20.576173782348633", "yaw": "270.3822937011719", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.54", "y": "4.45", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "4.87", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.49", "y": "89.92", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.99", "y": "90.38", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.81, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.54", "y": "4.45", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "4.87", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.49", "y": "89.92", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.99", "y": "90.38", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.80860137939453", "y": "45.41740798950195", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.54", "y": "4.45", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "4.87", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.49", "y": "89.92", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.99", "y": "90.38", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.807186126708984", "y": "48.91740798950195", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.57", "y": "5.13", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.7", "y": "5.16", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.46", "y": "90.7", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.96", "y": "90.5", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.82, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.57", "y": "5.13", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.7", "y": "5.16", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.46", "y": "90.7", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.96", "y": "90.5", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.81857681274414", "y": "48.91741180419922", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.57", "y": "5.13", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.7", "y": "5.16", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.46", "y": "90.7", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.96", "y": "90.5", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.821407318115234", "y": "41.91741180419922", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -16.7, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-20.065515518188477", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.5749969482422", "y": "-23.56549072265625", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.63", "y": "11.73", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-13.065561294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -20.2, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-23.56553840637207", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-16.565584182739258", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.68", "y": "11.83", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6259765625", "y": "-13.065608024597168", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -23.8, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.6136016845703", "y": "-20.065608978271484", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.62635803222656", "y": "-16.565631866455078", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "145.79", "y": "11.93", "yaw": "257.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.63909912109375", "y": "-13.065655708312988", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.54", "y": "24.96", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.54", "y": "24.53", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.25", "y": "-60.50", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.75", "y": "-60.95", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 44.2, "y": -12.7, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.54", "y": "24.96", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.54", "y": "24.53", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.25", "y": "-60.50", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.75", "y": "-60.95", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.187618255615234", "y": "-16.09782600402832", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.54", "y": "24.96", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.54", "y": "24.53", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.25", "y": "-60.50", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.75", "y": "-60.95", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.174869537353516", "y": "-19.597803115844727", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.57", "y": "24.28", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.57", "y": "24.24", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.22", "y": "-60.65", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.72", "y": "-60.62", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 44.2, "y": -16.1, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.57", "y": "24.28", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.57", "y": "24.24", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.22", "y": "-60.65", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.72", "y": "-60.62", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.187252044677734", "y": "-19.597848892211914", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.57", "y": "24.28", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.57", "y": "24.24", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.22", "y": "-60.65", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.72", "y": "-60.62", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.212745666503906", "y": "-12.597894668579102", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.91, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.90859985351562", "y": "45.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9071807861328", "y": "48.9715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-150.84", "y": "9.37", "yaw": "79.648041", "z": "1.0" }, { "pitch": "0.0", "x": "-154.90", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.90577697753906", "y": "52.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.92, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.91854858398438", "y": "48.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.91714477539062", "y": "52.47157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.47", "y": "10.96", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.92138671875", "y": "41.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.93, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9285888671875", "y": "52.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.93141174316406", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-155.18", "y": "11.27", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.93283081054688", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -178.93, "y": 52.88, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9315643310547", "y": "48.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9329833984375", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-154.82", "y": "11.32", "yaw": "79.648041", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-178.9344024658203", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.60", "y": "24.37", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.60", "y": "24.39", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.18", "y": "-60.36", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.69", "y": "-61.16", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 44.2, "y": -19.7, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.60", "y": "24.37", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.60", "y": "24.39", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.18", "y": "-60.36", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.69", "y": "-61.16", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.21311569213867", "y": "-16.097919464111328", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "2.60", "y": "24.37", "yaw": "269.471191", "z": "1.0" }, { "pitch": "0.0", "x": "6.60", "y": "24.39", "yaw": "269.471191", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.18", "y": "-60.36", "yaw": "89.471161", "z": "1.0" }, { "pitch": "0.0", "x": "-8.69", "y": "-61.16", "yaw": "89.471161", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "44.225860595703125", "y": "-12.597942352294922", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 658.6, "y": 82.95, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2265625", "y": "82.98932647705078", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.726318359375", "y": "83.02729034423828", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.2261352539062", "y": "83.06524658203125", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.69", "y": "51.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.70", "y": "48.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.71", "y": "44.84", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.72", "y": "41.34", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.73", "y": "37.84", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7259521484375", "y": "83.10320281982422", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 662.3, "y": 83.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "665.7197265625", "y": "83.63709259033203", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.2195434570312", "y": "83.675048828125", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7193603515625", "y": "83.71300506591797", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "51.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "44.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "37.94", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.7201538085938", "y": "83.56117248535156", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 665.8, "y": 83.17, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "669.224609375", "y": "83.20713806152344", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "672.7244262695312", "y": "83.2450942993164", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "662.2250366210938", "y": "83.13121795654297", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "621.39", "y": "52.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.40", "y": "48.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.41", "y": "45.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.42", "y": "41.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "621.43", "y": "38.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "658.7252197265625", "y": "83.09326171875", "yaw": "270.62139892578125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.60", "y": "5.4", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.10", "y": "5.1", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.42", "y": "89.78", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.93", "y": "90.59", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.83, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.60", "y": "5.4", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.10", "y": "5.1", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.42", "y": "89.78", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.93", "y": "90.59", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.83143615722656", "y": "45.41741943359375", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-5.60", "y": "5.4", "yaw": "89.648071", "z": "1.0" }, { "pitch": "0.0", "x": "-9.10", "y": "5.1", "yaw": "89.648071", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "4.42", "y": "89.78", "yaw": "269.648071", "z": "1.0" }, { "pitch": "0.0", "x": "7.93", "y": "90.59", "yaw": "269.648071", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-44.83285140991211", "y": "41.91741943359375", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-52.21", "y": "41.88", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.24", "y": "45.48", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.28", "y": "48.98", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 1.96, "y": 83.3, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-52.21", "y": "41.88", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.24", "y": "45.48", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-52.28", "y": "48.98", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.747596740722656", "y": "83.26728820800781", "yaw": "269.5051574707031", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-51.93", "y": "41.86", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.96", "y": "45.46", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.0", "y": "48.96", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.66, "y": 83.4, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-51.93", "y": "41.86", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.96", "y": "45.46", "yaw": "0.573578", "z": "1.0" }, { "pitch": "0.0", "x": "-51.0", "y": "48.96", "yaw": "0.573578", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.2488670349121094", "y": "83.4294662475586", "yaw": "269.5051574707031", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.18", "y": "42.22", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.72", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.20", "y": "49.22", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.51, "y": 10.56, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.18", "y": "42.22", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.72", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.20", "y": "49.22", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.104096412658691", "y": "10.536018371582031", "yaw": "90.3823013305664", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.10", "y": "42.28", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.78", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.24", "y": "49.28", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.0, "y": 10.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-51.10", "y": "42.28", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.21", "y": "45.78", "yaw": "0.427795", "z": "1.0" }, { "pitch": "0.0", "x": "-51.24", "y": "49.28", "yaw": "0.427795", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.604596138000488", "y": "10.62265682220459", "yaw": "90.3823013305664", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "207.99", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.60", "y": "208.3", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-41.5", "y": "239.29", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-41.1", "y": "242.79", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 9.4, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "207.99", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.60", "y": "208.3", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-41.5", "y": "239.29", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-41.1", "y": "242.79", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "12.778694152832031", "y": "276.646728515625", "yaw": "-90.90380859375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.12", "y": "207.99", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.60", "y": "208.3", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-41.5", "y": "239.29", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-41.1", "y": "242.79", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "5.77956485748291", "y": "276.75714111328125", "yaw": "-90.90380859375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 239.9, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.6988410949707", "y": "243.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68668746948242", "y": "246.61331176757812", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.11", "y": "208.48", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-6.61", "y": "208.52", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.31", "y": "208.57", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.674537658691406", "y": "250.11329650878906", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "138.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-40.11", "y": "239.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.10", "y": "243.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.8", "y": "247.10", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.7", "y": "250.60", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -10.2, "y": 213.5, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-40.11", "y": "239.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.10", "y": "243.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.8", "y": "247.10", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.7", "y": "250.60", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.720656394958496", "y": "213.4451141357422", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-40.11", "y": "239.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.10", "y": "243.60", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.8", "y": "247.10", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-40.7", "y": "250.60", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2210917472839355", "y": "213.38990783691406", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6298828125", "y": "138.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6454467773438", "y": "138.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 657.7, "y": 183.15, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1398315429688", "y": "183.1873016357422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6395874023438", "y": "183.2252655029297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.139404296875", "y": "183.2632293701172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.4", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6392211914062", "y": "183.30117797851562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 661.7, "y": 183.26, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6388549804688", "y": "183.2918701171875", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.138671875", "y": "183.329833984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6384887695312", "y": "183.36778259277344", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.14", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.64", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.14", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.6392822265625", "y": "183.21595764160156", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.658935546875", "y": "138.49703979492188", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 665.2, "y": 183.37, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.137939453125", "y": "183.40187072753906", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6377563476562", "y": "183.4398193359375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1383666992188", "y": "183.32594299316406", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.24", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.74", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.24", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.6385498046875", "y": "183.28799438476562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 668.99, "y": 183.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "671.6359252929688", "y": "183.60870361328125", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6362915039062", "y": "183.5327911376953", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1365356445312", "y": "183.4948272705078", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.79", "y": "152.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.80", "y": "148.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.81", "y": "145.44", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.82", "y": "141.94", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.83", "y": "138.44", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.63671875", "y": "183.45687866210938", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 672.3, "y": 183.7, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "668.1351928710938", "y": "183.6548309326172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "664.6353759765625", "y": "183.6168670654297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "661.1356201171875", "y": "183.5789031982422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "620.89", "y": "152.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.90", "y": "149.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.91", "y": "145.54", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.92", "y": "142.4", "yaw": "0.177307", "z": "1.0" }, { "pitch": "0.0", "x": "620.93", "y": "138.54", "yaw": "0.177307", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "657.6358032226562", "y": "183.54095458984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 172.6, "y": -13.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.58847045898438", "y": "-16.565494537353516", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.57571411132812", "y": "-20.065471649169922", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "142.14", "y": "14.34", "yaw": "258.370605", "z": "1.0" }, { "pitch": "0.0", "x": "145.41", "y": "11.90", "yaw": "257.552917", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "172.56297302246094", "y": "-23.565448760986328", "yaw": "179.79132080078125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.23", "y": "207.94", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.72", "y": "207.98", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-40.85", "y": "239.24", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-40.81", "y": "242.74", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.23", "y": "207.94", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.72", "y": "207.98", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-40.85", "y": "239.24", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-40.81", "y": "242.74", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "9.278183937072754", "y": "276.6419982910156", "yaw": "-90.90380859375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.23", "y": "207.94", "yaw": "89.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-6.72", "y": "207.98", "yaw": "89.320801", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-40.85", "y": "239.24", "yaw": "359.320801", "z": "1.0" }, { "pitch": "0.0", "x": "-40.81", "y": "242.74", "yaw": "359.320801", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "12.777749061584473", "y": "276.5867919921875", "yaw": "-90.90380859375", "z": "0.0" } } ], "scenario_type": "Scenario7" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } } ], "scenario_type": "Scenario8" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.24", "y": "208.23", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } } ], "scenario_type": "Scenario9" }, { "available_event_configurations": [], "scenario_type": "Scenario10" } ] } ] } ================================================ FILE: leaderboard/leaderboard/__init__.py ================================================ ================================================ FILE: leaderboard/leaderboard/autoagents/__init__.py ================================================ ================================================ FILE: leaderboard/leaderboard/autoagents/agent_wrapper.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Wrapper for autonomous agents required for tracking and checking of used sensors """ from __future__ import print_function import math import os import time import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from leaderboard.envs.sensor_interface import CallBack, OpenDriveMapReader, SpeedometerReader, SensorConfigurationInvalid from leaderboard.autoagents.autonomous_agent import Track MAX_ALLOWED_RADIUS_SENSOR = 3.0 MAX_ALLOWED_RADIUS_SENSOR = 1000.0 # increased for topdown map generation SENSORS_LIMITS = { 'sensor.camera.rgb': 10, 'sensor.camera.semantic_segmentation': 10, 'sensor.camera.depth': 10, 'sensor.lidar.ray_cast': 1, 'sensor.lidar.ray_cast_semantic': 1, 'sensor.other.radar': 2, 'sensor.other.gnss': 1, 'sensor.other.imu': 1, 'sensor.opendrive_map': 1, 'sensor.speedometer': 1 } class AgentError(Exception): """ Exceptions thrown when the agent returns an error during the simulation """ def __init__(self, message): super(AgentError, self).__init__(message) class AgentWrapper(object): """ Wrapper for autonomous agents required for tracking and checking of used sensors """ allowed_sensors = [ 'sensor.opendrive_map', 'sensor.speedometer', 'sensor.camera.rgb', 'sensor.camera.semantic_segmentation', 'sensor.camera.depth', 'sensor.camera', 'sensor.lidar.ray_cast', 'sensor.lidar.ray_cast_semantic', 'sensor.other.radar', 'sensor.other.gnss', 'sensor.other.imu' ] _agent = None _sensors_list = [] def __init__(self, agent): """ Set the autonomous agent """ self._agent = agent def __call__(self): """ Pass the call directly to the agent """ return self._agent() def setup_sensors(self, vehicle, debug_mode=False): """ Create the sensors defined by the user and attach them to the ego-vehicle :param vehicle: ego vehicle :return: """ bp_library = CarlaDataProvider.get_world().get_blueprint_library() for sensor_spec in self._agent.sensors(): # These are the pseudosensors (not spawned) if sensor_spec['type'].startswith('sensor.opendrive_map'): # The HDMap pseudo sensor is created directly here sensor = OpenDriveMapReader(vehicle, sensor_spec['reading_frequency']) elif sensor_spec['type'].startswith('sensor.speedometer'): delta_time = CarlaDataProvider.get_world().get_settings().fixed_delta_seconds frame_rate = 1 / delta_time sensor = SpeedometerReader(vehicle, frame_rate) # These are the sensors spawned on the carla world else: bp = bp_library.find(str(sensor_spec['type'])) if sensor_spec['type'].startswith('sensor.camera.semantic_segmentation'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) bp.set_attribute('lens_circle_multiplier', str(3.0)) bp.set_attribute('lens_circle_falloff', str(3.0)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.camera.depth'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) bp.set_attribute('lens_circle_multiplier', str(3.0)) bp.set_attribute('lens_circle_falloff', str(3.0)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.camera'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) bp.set_attribute('lens_circle_multiplier', str(3.0)) bp.set_attribute('lens_circle_falloff', str(3.0)) bp.set_attribute('chromatic_aberration_intensity', str(0.5)) bp.set_attribute('chromatic_aberration_offset', str(0)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.lidar.ray_cast_semantic'): bp.set_attribute('range', str(85)) bp.set_attribute('rotation_frequency', str(10)) # default: 10, change to 20 for old lidar models bp.set_attribute('channels', str(64)) bp.set_attribute('upper_fov', str(10)) bp.set_attribute('lower_fov', str(-30)) bp.set_attribute('points_per_second', str(600000)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(85)) bp.set_attribute('rotation_frequency', str(10)) # default: 10, change to 20 to generate 360 degree LiDAR point cloud bp.set_attribute('channels', str(64)) bp.set_attribute('upper_fov', str(10)) bp.set_attribute('lower_fov', str(-30)) bp.set_attribute('points_per_second', str(600000)) bp.set_attribute('atmosphere_attenuation_rate', str(0.004)) bp.set_attribute('dropoff_general_rate', str(0.45)) bp.set_attribute('dropoff_intensity_limit', str(0.8)) bp.set_attribute('dropoff_zero_intensity', str(0.4)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.other.radar'): bp.set_attribute('horizontal_fov', str(sensor_spec['fov'])) # degrees bp.set_attribute('vertical_fov', str(sensor_spec['fov'])) # degrees bp.set_attribute('points_per_second', '1500') bp.set_attribute('range', '100') # meters sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.other.gnss'): # bp.set_attribute('noise_alt_stddev', str(0.000005)) # bp.set_attribute('noise_lat_stddev', str(0.000005)) # bp.set_attribute('noise_lon_stddev', str(0.000005)) bp.set_attribute('noise_alt_bias', str(0.0)) bp.set_attribute('noise_lat_bias', str(0.0)) bp.set_attribute('noise_lon_bias', str(0.0)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() elif sensor_spec['type'].startswith('sensor.other.imu'): bp.set_attribute('noise_accel_stddev_x', str(0.001)) bp.set_attribute('noise_accel_stddev_y', str(0.001)) bp.set_attribute('noise_accel_stddev_z', str(0.015)) bp.set_attribute('noise_gyro_stddev_x', str(0.001)) bp.set_attribute('noise_gyro_stddev_y', str(0.001)) bp.set_attribute('noise_gyro_stddev_z', str(0.001)) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) # create sensor sensor_transform = carla.Transform(sensor_location, sensor_rotation) sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle) # setup callback sensor.listen(CallBack(sensor_spec['id'], sensor_spec['type'], sensor, self._agent.sensor_interface)) self._sensors_list.append(sensor) # Tick once to spawn the sensors CarlaDataProvider.get_world().tick() @staticmethod def validate_sensor_configuration(sensors, agent_track, selected_track): """ Ensure that the sensor configuration is valid, in case the challenge mode is used Returns true on valid configuration, false otherwise """ if Track(selected_track) != agent_track: raise SensorConfigurationInvalid("You are submitting to the wrong track [{}]!".format(Track(selected_track))) sensor_count = {} sensor_ids = [] for sensor in sensors: # Check if the is has been already used sensor_id = sensor['id'] if sensor_id in sensor_ids: raise SensorConfigurationInvalid("Duplicated sensor tag [{}]".format(sensor_id)) else: sensor_ids.append(sensor_id) # Check if the sensor is valid if agent_track == Track.SENSORS: if sensor['type'].startswith('sensor.opendrive_map'): raise SensorConfigurationInvalid("Illegal sensor used for Track [{}]!".format(agent_track)) # Check the sensors validity if sensor['type'] not in AgentWrapper.allowed_sensors: raise SensorConfigurationInvalid("Illegal sensor used. {} are not allowed!".format(sensor['type'])) # Check the extrinsics of the sensor if 'x' in sensor and 'y' in sensor and 'z' in sensor: if math.sqrt(sensor['x']**2 + sensor['y']**2 + sensor['z']**2) > MAX_ALLOWED_RADIUS_SENSOR: raise SensorConfigurationInvalid( "Illegal sensor extrinsics used for Track [{}]!".format(agent_track)) # Check the amount of sensors if sensor['type'] in sensor_count: sensor_count[sensor['type']] += 1 else: sensor_count[sensor['type']] = 1 for sensor_type, max_instances_allowed in SENSORS_LIMITS.items(): if sensor_type in sensor_count and sensor_count[sensor_type] > max_instances_allowed: raise SensorConfigurationInvalid( "Too many {} used! " "Maximum number allowed is {}, but {} were requested.".format(sensor_type, max_instances_allowed, sensor_count[sensor_type])) def cleanup(self): """ Remove and destroy all sensors """ for i, _ in enumerate(self._sensors_list): if self._sensors_list[i] is not None: self._sensors_list[i].stop() self._sensors_list[i].destroy() self._sensors_list[i] = None self._sensors_list = [] ================================================ FILE: leaderboard/leaderboard/autoagents/autonomous_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides the base class for all autonomous agents """ from __future__ import print_function from enum import Enum import carla from srunner.scenariomanager.timer import GameTime from leaderboard.utils.route_manipulation import downsample_route from leaderboard.envs.sensor_interface import SensorInterface class Track(Enum): """ This enum represents the different tracks of the CARLA AD leaderboard. """ SENSORS = 'SENSORS' MAP = 'MAP' class AutonomousAgent(object): """ Autonomous agent base class. All user agents have to be derived from this class """ def __init__(self, path_to_conf_file): self.track = Track.SENSORS # current global plans to reach a destination self._global_plan = None self._global_plan_world_coord = None # this data structure will contain all sensor data self.sensor_interface = SensorInterface() # agent's initialization self.setup(path_to_conf_file) self.wallclock_t0 = None def setup(self, path_to_conf_file): """ Initialize everything needed by your agent and set the track attribute to the right type: Track.SENSORS : CAMERAS, LIDAR, RADAR, GPS and IMU sensors are allowed Track.MAP : OpenDRIVE map is also allowed """ pass def sensors(self): # pylint: disable=no-self-use """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} ] """ sensors = [] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. :return: control """ control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False return control def destroy(self): """ Destroy (clean-up) the agent :return: """ pass def __call__(self): """ Execute the agent call, e.g. agent() Returns the next vehicle controls """ input_data = self.sensor_interface.get_data() timestamp = GameTime.get_time() if not self.wallclock_t0: self.wallclock_t0 = GameTime.get_wallclocktime() wallclock = GameTime.get_wallclocktime() wallclock_diff = (wallclock - self.wallclock_t0).total_seconds() # print('======[Agent] Wallclock_time = {} / {} / Sim_time = {} / {}x'.format(wallclock, wallclock_diff, timestamp, timestamp/(wallclock_diff+0.001))) control = self.run_step(input_data, timestamp) control.manual_gear_shift = False return control def set_global_plan(self, global_plan_gps, global_plan_world_coord, wp=None): """ Set the plan (route) for the agent """ ds_ids = downsample_route(global_plan_world_coord, 50) self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1]) for x in ds_ids] self._global_plan = [global_plan_gps[x] for x in ds_ids] ================================================ FILE: leaderboard/leaderboard/autoagents/dummy_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a dummy agent to control the ego vehicle """ from __future__ import print_function import carla from leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track def get_entry_point(): return 'DummyAgent' class DummyAgent(AutonomousAgent): """ Dummy autonomous agent to control the ego vehicle """ def setup(self, path_to_conf_file): """ Setup the agent parameters """ self.track = Track.MAP def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} ] """ sensors = [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'id': 'LIDAR'}, {'type': 'sensor.other.radar', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'fov': 30, 'id': 'RADAR'}, {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'}, {'type': 'sensor.other.imu', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'id': 'IMU'}, {'type': 'sensor.opendrive_map', 'reading_frequency': 1, 'id': 'OpenDRIVE'}, ] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ print("=====================>") for key, val in input_data.items(): if hasattr(val[1], 'shape'): shape = val[1].shape print("[{} -- {:06d}] with shape {}".format(key, val[0], shape)) else: print("[{} -- {:06d}] ".format(key, val[0])) print("<=====================") # DO SOMETHING SMART # RETURN CONTROL control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False return control ================================================ FILE: leaderboard/leaderboard/autoagents/human_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a human agent to control the ego vehicle via keyboard """ import time import json from threading import Thread import cv2 import numpy as np try: import pygame from pygame.locals import K_DOWN from pygame.locals import K_LEFT from pygame.locals import K_RIGHT from pygame.locals import K_SPACE from pygame.locals import K_UP from pygame.locals import K_a from pygame.locals import K_d from pygame.locals import K_s from pygame.locals import K_w from pygame.locals import K_q except ImportError: raise RuntimeError('cannot import pygame, make sure pygame package is installed') import carla from leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track def get_entry_point(): return 'HumanAgent' class HumanInterface(object): """ Class to control a vehicle manually for debugging purposes """ def __init__(self): self._width = 800 self._height = 600 self._surface = None pygame.init() pygame.font.init() self._clock = pygame.time.Clock() self._display = pygame.display.set_mode((self._width, self._height), pygame.HWSURFACE | pygame.DOUBLEBUF) pygame.display.set_caption("Human Agent") def run_interface(self, input_data): """ Run the GUI """ # process sensor data image_center = input_data['Center'][1][:, :, -2::-1] # display image self._surface = pygame.surfarray.make_surface(image_center.swapaxes(0, 1)) if self._surface is not None: self._display.blit(self._surface, (0, 0)) pygame.display.flip() def _quit(self): pygame.quit() class HumanAgent(AutonomousAgent): """ Human agent to control the ego vehicle via keyboard """ current_control = None agent_engaged = False def setup(self, path_to_conf_file): """ Setup the agent parameters """ self.track = Track.SENSORS self.agent_engaged = False self._hic = HumanInterface() self._controller = KeyboardControl(path_to_conf_file) self._prev_timestamp = 0 def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} ] """ sensors = [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'}, {'type': 'sensor.speedometer', 'reading_frequency': 20, 'id': 'speed'}, ] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ self.agent_engaged = True self._hic.run_interface(input_data) control = self._controller.parse_events(timestamp - self._prev_timestamp) self._prev_timestamp = timestamp return control def destroy(self): """ Cleanup """ self._hic._quit = True class KeyboardControl(object): """ Keyboard control for the human agent """ def __init__(self, path_to_conf_file): """ Init """ self._control = carla.VehicleControl() self._steer_cache = 0.0 self._clock = pygame.time.Clock() # Get the mode if path_to_conf_file: with (open(path_to_conf_file, "r")) as f: lines = f.read().split("\n") self._mode = lines[0].split(" ")[1] self._endpoint = lines[1].split(" ")[1] # Get the needed vars if self._mode == "log": self._log_data = {'records': []} elif self._mode == "playback": self._index = 0 self._control_list = [] with open(self._endpoint) as fd: try: self._records = json.load(fd) self._json_to_control() except json.JSONDecodeError: pass else: self._mode = "normal" self._endpoint = None def _json_to_control(self): # transform strs into VehicleControl commands for entry in self._records['records']: control = carla.VehicleControl(throttle=entry['control']['throttle'], steer=entry['control']['steer'], brake=entry['control']['brake'], hand_brake=entry['control']['hand_brake'], reverse=entry['control']['reverse'], manual_gear_shift=entry['control']['manual_gear_shift'], gear=entry['control']['gear']) self._control_list.append(control) def parse_events(self, timestamp): """ Parse the keyboard events and set the vehicle controls accordingly """ # Move the vehicle if self._mode == "playback": self._parse_json_control() else: self._parse_vehicle_keys(pygame.key.get_pressed(), timestamp*1000) # Record the control if self._mode == "log": self._record_control() return self._control def _parse_vehicle_keys(self, keys, milliseconds): """ Calculate new vehicle controls based on input keys """ for event in pygame.event.get(): if event.type == pygame.QUIT: return elif event.type == pygame.KEYUP: if event.key == K_q: self._control.gear = 1 if self._control.reverse else -1 self._control.reverse = self._control.gear < 0 if keys[K_UP] or keys[K_w]: self._control.throttle = 0.6 else: self._control.throttle = 0.0 steer_increment = 3e-4 * milliseconds if keys[K_LEFT] or keys[K_a]: self._steer_cache -= steer_increment elif keys[K_RIGHT] or keys[K_d]: self._steer_cache += steer_increment else: self._steer_cache = 0.0 steer_cache = min(0.95, max(-0.95, self._steer_cache)) self._control.steer = round(self._steer_cache, 1) self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0 self._control.hand_brake = keys[K_SPACE] def _parse_json_control(self): if self._index < len(self._control_list): self._control = self._control_list[self._index] self._index += 1 else: print("JSON file has no more entries") def _record_control(self): new_record = { 'control': { 'throttle': self._control.throttle, 'steer': self._control.steer, 'brake': self._control.brake, 'hand_brake': self._control.hand_brake, 'reverse': self._control.reverse, 'manual_gear_shift': self._control.manual_gear_shift, 'gear': self._control.gear } } self._log_data['records'].append(new_record) def __del__(self): # Get ready to log user commands if self._mode == "log" and self._log_data: with open(self._endpoint, 'w') as fd: json.dump(self._log_data, fd, indent=4, sort_keys=True) ================================================ FILE: leaderboard/leaderboard/autoagents/human_agent_config.txt ================================================ mode: log # Either 'log' or 'playback' file: test.json # path to the file with the controls This is the configuration file of the human agent. This agent incorporates two modes. The log mode parses the controls given to the vehicle into a dictionary and records them into a .json file. This file can be read by the playback mode to control the vehicle in the same way, resulting in a deterministic agent. The file name can be chosen, and is the second argument of this config file. ================================================ FILE: leaderboard/leaderboard/autoagents/npc_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an NPC agent to control the ego vehicle """ from __future__ import print_function import carla from agents.navigation.basic_agent import BasicAgent from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track def get_entry_point(): return 'NpcAgent' class NpcAgent(AutonomousAgent): """ NPC autonomous agent to control the ego vehicle """ _agent = None _route_assigned = False def setup(self, path_to_conf_file): """ Setup the agent parameters """ self.track = Track.SENSORS self._route_assigned = False self._agent = None def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} ] """ sensors = [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, ] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False if not self._agent: hero_actor = None for actor in CarlaDataProvider.get_world().get_actors(): if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero': hero_actor = actor break if hero_actor: self._agent = BasicAgent(hero_actor) return control if not self._route_assigned: if self._global_plan: plan = [] prev = None for transform, _ in self._global_plan_world_coord: wp = CarlaDataProvider.get_map().get_waypoint(transform.location) if prev: route_segment = self._agent._trace_route(prev, wp) plan.extend(route_segment) prev = wp #loc = plan[-1][0].transform.location #self._agent.set_destination([loc.x, loc.y, loc.z]) self._agent._local_planner.set_global_plan(plan) # pylint: disable=protected-access self._route_assigned = True else: control = self._agent.run_step() return control ================================================ FILE: leaderboard/leaderboard/autoagents/ros_agent.py ================================================ #!/usr/bin/env python # # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . # """ This module provides a ROS autonomous agent interface to control the ego vehicle via a ROS stack """ import math import os import subprocess import signal import threading import time import numpy import carla import rospy from cv_bridge import CvBridge from geometry_msgs.msg import PoseStamped from nav_msgs.msg import Odometry, Path from rosgraph_msgs.msg import Clock from sensor_msgs.msg import Image, PointCloud2, NavSatFix, NavSatStatus, CameraInfo from sensor_msgs.point_cloud2 import create_cloud_xyz32 from std_msgs.msg import Header, String import tf # pylint: disable=line-too-long from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, CarlaEgoVehicleControl, CarlaWorldInfo # pylint: enable=line-too-long from leaderboard.autoagents.autonomous_agent import AutonomousAgent, Track class RosAgent(AutonomousAgent): """ Base class for ROS-based stacks. Derive from it and implement the sensors() method. Please define TEAM_CODE_ROOT in your environment. The stack is started by executing $TEAM_CODE_ROOT/start.sh The sensor data is published on similar topics as with the carla-ros-bridge. You can find details about the utilized datatypes there. This agent expects a roscore to be running. """ speed = None current_control = None stack_process = None timestamp = None current_map_name = None step_mode_possible = None vehicle_info_publisher = None global_plan_published = None def setup(self, path_to_conf_file): """ setup agent """ self.track = Track.MAP self.stack_thread = None # get start_script from environment team_code_path = os.environ['TEAM_CODE_ROOT'] if not team_code_path or not os.path.exists(team_code_path): raise IOError("Path '{}' defined by TEAM_CODE_ROOT invalid".format(team_code_path)) start_script = "{}/start.sh".format(team_code_path) if not os.path.exists(start_script): raise IOError("File '{}' defined by TEAM_CODE_ROOT invalid".format(start_script)) # set use_sim_time via commandline before init-node process = subprocess.Popen( "rosparam set use_sim_time true", shell=True, stderr=subprocess.STDOUT, stdout=subprocess.PIPE) process.wait() if process.returncode: raise RuntimeError("Could not set use_sim_time") # initialize ros node rospy.init_node('ros_agent', anonymous=True) # publish first clock value '0' self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10, latch=True) self.clock_publisher.publish(Clock(rospy.Time.from_sec(0))) # execute script that starts the ad stack (remains running) rospy.loginfo("Executing stack...") self.stack_process = subprocess.Popen(start_script, shell=True, preexec_fn=os.setpgrp) self.vehicle_control_event = threading.Event() self.timestamp = None self.speed = 0 self.global_plan_published = False self.vehicle_info_publisher = None self.vehicle_status_publisher = None self.odometry_publisher = None self.world_info_publisher = None self.map_file_publisher = None self.current_map_name = None self.tf_broadcaster = None self.step_mode_possible = False self.vehicle_control_subscriber = rospy.Subscriber( '/carla/ego_vehicle/vehicle_control_cmd', CarlaEgoVehicleControl, self.on_vehicle_control) self.current_control = carla.VehicleControl() self.waypoint_publisher = rospy.Publisher( '/carla/ego_vehicle/waypoints', Path, queue_size=1, latch=True) self.publisher_map = {} self.id_to_sensor_type_map = {} self.id_to_camera_info_map = {} self.cv_bridge = CvBridge() # setup ros publishers for sensors # pylint: disable=line-too-long for sensor in self.sensors(): self.id_to_sensor_type_map[sensor['id']] = sensor['type'] if sensor['type'] == 'sensor.camera.rgb': self.publisher_map[sensor['id']] = rospy.Publisher( '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + "/image_color", Image, queue_size=1, latch=True) self.id_to_camera_info_map[sensor['id']] = self.build_camera_info(sensor) self.publisher_map[sensor['id'] + '_info'] = rospy.Publisher( '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + "/camera_info", CameraInfo, queue_size=1, latch=True) elif sensor['type'] == 'sensor.lidar.ray_cast': self.publisher_map[sensor['id']] = rospy.Publisher( '/carla/ego_vehicle/lidar/' + sensor['id'] + "/point_cloud", PointCloud2, queue_size=1, latch=True) elif sensor['type'] == 'sensor.other.gnss': self.publisher_map[sensor['id']] = rospy.Publisher( '/carla/ego_vehicle/gnss/' + sensor['id'] + "/fix", NavSatFix, queue_size=1, latch=True) elif sensor['type'] == 'sensor.can_bus': if not self.vehicle_info_publisher: self.vehicle_info_publisher = rospy.Publisher( '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True) if not self.vehicle_status_publisher: self.vehicle_status_publisher = rospy.Publisher( '/carla/ego_vehicle/vehicle_status', CarlaEgoVehicleStatus, queue_size=1, latch=True) elif sensor['type'] == 'sensor.hd_map': if not self.odometry_publisher: self.odometry_publisher = rospy.Publisher( '/carla/ego_vehicle/odometry', Odometry, queue_size=1, latch=True) if not self.world_info_publisher: self.world_info_publisher = rospy.Publisher( '/carla/world_info', CarlaWorldInfo, queue_size=1, latch=True) if not self.map_file_publisher: self.map_file_publisher = rospy.Publisher('/carla/map_file', String, queue_size=1, latch=True) if not self.tf_broadcaster: self.tf_broadcaster = tf.TransformBroadcaster() else: raise TypeError("Invalid sensor type: {}".format(sensor['type'])) # pylint: enable=line-too-long def destroy(self): """ Cleanup of all ROS publishers """ if self.stack_process and self.stack_process.poll() is None: rospy.loginfo("Sending SIGTERM to stack...") os.killpg(os.getpgid(self.stack_process.pid), signal.SIGTERM) rospy.loginfo("Waiting for termination of stack...") self.stack_process.wait() time.sleep(5) rospy.loginfo("Terminated stack.") rospy.loginfo("Stack is no longer running") self.world_info_publisher.unregister() self.map_file_publisher.unregister() self.vehicle_status_publisher.unregister() self.vehicle_info_publisher.unregister() self.waypoint_publisher.unregister() self.stack_process = None rospy.loginfo("Cleanup finished") def on_vehicle_control(self, data): """ callback if a new vehicle control command is received """ cmd = carla.VehicleControl() cmd.throttle = data.throttle cmd.steer = data.steer cmd.brake = data.brake cmd.hand_brake = data.hand_brake cmd.reverse = data.reverse cmd.gear = data.gear cmd.manual_gear_shift = data.manual_gear_shift self.current_control = cmd if not self.vehicle_control_event.is_set(): self.vehicle_control_event.set() # After the first vehicle control is sent out, it is possible to use the stepping mode self.step_mode_possible = True def build_camera_info(self, attributes): # pylint: disable=no-self-use """ Private function to compute camera info camera info doesn't change over time """ camera_info = CameraInfo() # store info without header camera_info.header = None camera_info.width = int(attributes['width']) camera_info.height = int(attributes['height']) camera_info.distortion_model = 'plumb_bob' cx = camera_info.width / 2.0 cy = camera_info.height / 2.0 fx = camera_info.width / ( 2.0 * math.tan(float(attributes['fov']) * math.pi / 360.0)) fy = fx camera_info.K = [fx, 0, cx, 0, fy, cy, 0, 0, 1] camera_info.D = [0, 0, 0, 0, 0] camera_info.R = [1.0, 0, 0, 0, 1.0, 0, 0, 0, 1.0] camera_info.P = [fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1.0, 0] return camera_info def publish_plan(self): """ publish the global plan """ msg = Path() msg.header.frame_id = "/map" msg.header.stamp = rospy.Time.now() for wp in self._global_plan_world_coord: pose = PoseStamped() pose.pose.position.x = wp[0].location.x pose.pose.position.y = -wp[0].location.y pose.pose.position.z = wp[0].location.z quaternion = tf.transformations.quaternion_from_euler( 0, 0, -math.radians(wp[0].rotation.yaw)) pose.pose.orientation.x = quaternion[0] pose.pose.orientation.y = quaternion[1] pose.pose.orientation.z = quaternion[2] pose.pose.orientation.w = quaternion[3] msg.poses.append(pose) rospy.loginfo("Publishing Plan...") self.waypoint_publisher.publish(msg) def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors """ raise NotImplementedError( "This function has to be implemented by the derived classes") def get_header(self): """ Returns ROS message header """ header = Header() header.stamp = rospy.Time.from_sec(self.timestamp) return header def publish_lidar(self, sensor_id, data): """ Function to publish lidar data """ header = self.get_header() header.frame_id = 'ego_vehicle/lidar/{}'.format(sensor_id) lidar_data = numpy.frombuffer( data, dtype=numpy.float32) lidar_data = numpy.reshape( lidar_data, (int(lidar_data.shape[0] / 3), 3)) # we take the oposite of y axis # (as lidar point are express in left handed coordinate system, and ros need right handed) # we need a copy here, because the data are read only in carla numpy # array lidar_data = -1.0 * lidar_data # we also need to permute x and y lidar_data = lidar_data[..., [1, 0, 2]] msg = create_cloud_xyz32(header, lidar_data) self.publisher_map[sensor_id].publish(msg) def publish_gnss(self, sensor_id, data): """ Function to publish gnss data """ msg = NavSatFix() msg.header = self.get_header() msg.header.frame_id = 'gps' msg.latitude = data[0] msg.longitude = data[1] msg.altitude = data[2] msg.status.status = NavSatStatus.STATUS_SBAS_FIX # pylint: disable=line-too-long msg.status.service = NavSatStatus.SERVICE_GPS | NavSatStatus.SERVICE_GLONASS | NavSatStatus.SERVICE_COMPASS | NavSatStatus.SERVICE_GALILEO # pylint: enable=line-too-long self.publisher_map[sensor_id].publish(msg) def publish_camera(self, sensor_id, data): """ Function to publish camera data """ msg = self.cv_bridge.cv2_to_imgmsg(data, encoding='bgra8') # the camera data is in respect to the camera's own frame msg.header = self.get_header() msg.header.frame_id = 'ego_vehicle/camera/rgb/{}'.format(sensor_id) cam_info = self.id_to_camera_info_map[sensor_id] cam_info.header = msg.header self.publisher_map[sensor_id + '_info'].publish(cam_info) self.publisher_map[sensor_id].publish(msg) def publish_can(self, sensor_id, data): """ publish can data """ if not self.vehicle_info_publisher: self.vehicle_info_publisher = rospy.Publisher( '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True) info_msg = CarlaEgoVehicleInfo() for wheel in data['wheels']: wheel_info = CarlaEgoVehicleInfoWheel() wheel_info.tire_friction = wheel['tire_friction'] wheel_info.damping_rate = wheel['damping_rate'] wheel_info.steer_angle = wheel['steer_angle'] wheel_info.disable_steering = wheel['disable_steering'] info_msg.wheels.append(wheel_info) info_msg.max_rpm = data['max_rpm'] info_msg.moi = data['moi'] info_msg.damping_rate_full_throttle = data['damping_rate_full_throttle'] info_msg.damping_rate_zero_throttle_clutch_disengaged = data['damping_rate_zero_throttle_clutch_disengaged'] info_msg.use_gear_autobox = data['use_gear_autobox'] info_msg.clutch_strength = data['clutch_strength'] info_msg.mass = data['mass'] info_msg.drag_coefficient = data['drag_coefficient'] info_msg.center_of_mass.x = data['center_of_mass']['x'] info_msg.center_of_mass.y = data['center_of_mass']['y'] info_msg.center_of_mass.z = data['center_of_mass']['z'] self.vehicle_info_publisher.publish(info_msg) msg = CarlaEgoVehicleStatus() msg.header = self.get_header() msg.velocity = data['speed'] self.speed = data['speed'] # msg.acceleration msg.control.throttle = self.current_control.throttle msg.control.steer = self.current_control.steer msg.control.brake = self.current_control.brake msg.control.hand_brake = self.current_control.hand_brake msg.control.reverse = self.current_control.reverse msg.control.gear = self.current_control.gear msg.control.manual_gear_shift = self.current_control.manual_gear_shift self.vehicle_status_publisher.publish(msg) def publish_hd_map(self, sensor_id, data): """ publish hd map data """ roll = -math.radians(data['transform']['roll']) pitch = -math.radians(data['transform']['pitch']) yaw = -math.radians(data['transform']['yaw']) quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw) x = data['transform']['x'] y = -data['transform']['y'] z = data['transform']['z'] if self.odometry_publisher: odometry = Odometry() odometry.header.frame_id = 'map' odometry.header.stamp = rospy.Time.from_sec(self.timestamp) odometry.child_frame_id = 'base_link' odometry.pose.pose.position.x = x odometry.pose.pose.position.y = y odometry.pose.pose.position.z = z odometry.pose.pose.orientation.x = quat[0] odometry.pose.pose.orientation.y = quat[1] odometry.pose.pose.orientation.z = quat[2] odometry.pose.pose.orientation.w = quat[3] odometry.twist.twist.linear.x = self.speed odometry.twist.twist.linear.y = 0 odometry.twist.twist.linear.z = 0 self.odometry_publisher.publish(odometry) if self.world_info_publisher: # extract map name map_name = os.path.basename(data['map_file'])[:-4] if self.current_map_name != map_name: self.current_map_name = map_name world_info = CarlaWorldInfo() world_info.map_name = self.current_map_name world_info.opendrive = data['opendrive'] self.world_info_publisher.publish(world_info) if self.map_file_publisher: self.map_file_publisher.publish(data['map_file']) def use_stepping_mode(self): # pylint: disable=no-self-use """ Overload this function to use stepping mode! """ return False def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ self.vehicle_control_event.clear() self.timestamp = timestamp self.clock_publisher.publish(Clock(rospy.Time.from_sec(timestamp))) # check if stack is still running if self.stack_process and self.stack_process.poll() is not None: raise RuntimeError("Stack exited with: {} {}".format( self.stack_process.returncode, self.stack_process.communicate()[0])) # publish global plan to ROS once if self._global_plan_world_coord and not self.global_plan_published: self.global_plan_published = True self.publish_plan() new_data_available = False # publish data of all sensors for key, val in input_data.items(): new_data_available = True sensor_type = self.id_to_sensor_type_map[key] if sensor_type == 'sensor.camera.rgb': self.publish_camera(key, val[1]) elif sensor_type == 'sensor.lidar.ray_cast': self.publish_lidar(key, val[1]) elif sensor_type == 'sensor.other.gnss': self.publish_gnss(key, val[1]) elif sensor_type == 'sensor.can_bus': self.publish_can(key, val[1]) elif sensor_type == 'sensor.hd_map': self.publish_hd_map(key, val[1]) else: raise TypeError("Invalid sensor type: {}".format(sensor_type)) if self.use_stepping_mode(): if self.step_mode_possible and new_data_available: self.vehicle_control_event.wait() # if the stepping mode is not used or active, there is no need to wait here return self.current_control ================================================ FILE: leaderboard/leaderboard/envs/__init__.py ================================================ ================================================ FILE: leaderboard/leaderboard/envs/sensor_interface.py ================================================ import copy import logging import numpy as np import os import time from threading import Thread from queue import Queue from queue import Empty import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import GameTime def threaded(fn): def wrapper(*args, **kwargs): thread = Thread(target=fn, args=args, kwargs=kwargs) thread.setDaemon(True) thread.start() return thread return wrapper class SensorConfigurationInvalid(Exception): """ Exceptions thrown when the sensors used by the agent are not allowed for that specific submissions """ def __init__(self, message): super(SensorConfigurationInvalid, self).__init__(message) class SensorReceivedNoData(Exception): """ Exceptions thrown when the sensors used by the agent take too long to receive data """ def __init__(self, message): super(SensorReceivedNoData, self).__init__(message) class GenericMeasurement(object): def __init__(self, data, frame): self.data = data self.frame = frame class BaseReader(object): def __init__(self, vehicle, reading_frequency=1.0): self._vehicle = vehicle self._reading_frequency = reading_frequency self._callback = None self._run_ps = True self.run() def __call__(self): pass @threaded def run(self): first_time = True latest_time = GameTime.get_time() while self._run_ps: if self._callback is not None: current_time = GameTime.get_time() # Second part forces the sensors to send data at the first tick, regardless of frequency if current_time - latest_time > (1 / self._reading_frequency) \ or (first_time and GameTime.get_frame() != 0): self._callback(GenericMeasurement(self.__call__(), GameTime.get_frame())) latest_time = GameTime.get_time() first_time = False else: time.sleep(0.001) def listen(self, callback): # Tell that this function receives what the producer does. self._callback = callback def stop(self): self._run_ps = False def destroy(self): self._run_ps = False class SpeedometerReader(BaseReader): """ Sensor to measure the speed of the vehicle. """ MAX_CONNECTION_ATTEMPTS = 10 def _get_forward_speed(self, transform=None, velocity=None): """ Convert the vehicle transform directly to forward speed """ if not velocity: velocity = self._vehicle.get_velocity() if not transform: transform = self._vehicle.get_transform() vel_np = np.array([velocity.x, velocity.y, velocity.z]) pitch = np.deg2rad(transform.rotation.pitch) yaw = np.deg2rad(transform.rotation.yaw) orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)]) speed = np.dot(vel_np, orientation) return speed def __call__(self): """ We convert the vehicle physics information into a convenient dictionary """ # protect this access against timeout attempts = 0 while attempts < self.MAX_CONNECTION_ATTEMPTS: try: velocity = self._vehicle.get_velocity() transform = self._vehicle.get_transform() break except Exception: attempts += 1 time.sleep(0.2) continue return {'speed': self._get_forward_speed(transform=transform, velocity=velocity)} class OpenDriveMapReader(BaseReader): def __call__(self): return {'opendrive': CarlaDataProvider.get_map().to_opendrive()} class CallBack(object): def __init__(self, tag, sensor_type, sensor, data_provider): self._tag = tag self._data_provider = data_provider self._data_provider.register_sensor(tag, sensor_type, sensor) def __call__(self, data): if isinstance(data, carla.libcarla.Image): self._parse_image_cb(data, self._tag) elif isinstance(data, carla.libcarla.LidarMeasurement): self._parse_lidar_cb(data, self._tag) elif isinstance(data, carla.libcarla.SemanticLidarMeasurement): self._parse_semantic_lidar_cb(data, self._tag) elif isinstance(data, carla.libcarla.RadarMeasurement): self._parse_radar_cb(data, self._tag) elif isinstance(data, carla.libcarla.GnssMeasurement): self._parse_gnss_cb(data, self._tag) elif isinstance(data, carla.libcarla.IMUMeasurement): self._parse_imu_cb(data, self._tag) elif isinstance(data, GenericMeasurement): self._parse_pseudosensor(data, self._tag) else: logging.error('No callback method for this sensor.') # Parsing CARLA physical Sensors def _parse_image_cb(self, image, tag): array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) array = copy.deepcopy(array) array = np.reshape(array, (image.height, image.width, 4)) self._data_provider.update_sensor(tag, array, image.frame) def _parse_lidar_cb(self, lidar_data, tag): points = np.frombuffer(lidar_data.raw_data, dtype=np.dtype('f4')) points = copy.deepcopy(points) points = np.reshape(points, (int(points.shape[0] / 4), 4)) self._data_provider.update_sensor(tag, points, lidar_data.frame) def _parse_semantic_lidar_cb(self, semantic_lidar_data, tag): points = np.frombuffer(semantic_lidar_data.raw_data, dtype=np.dtype('f4')) points = copy.deepcopy(points) points = np.reshape(points, (int(points.shape[0] / 6), 6)) self._data_provider.update_sensor(tag, points, semantic_lidar_data.frame) def _parse_radar_cb(self, radar_data, tag): # [depth, azimuth, altitute, velocity] points = np.frombuffer(radar_data.raw_data, dtype=np.dtype('f4')) points = copy.deepcopy(points) points = np.reshape(points, (int(points.shape[0] / 4), 4)) points = np.flip(points, 1) self._data_provider.update_sensor(tag, points, radar_data.frame) def _parse_gnss_cb(self, gnss_data, tag): array = np.array([gnss_data.latitude, gnss_data.longitude, gnss_data.altitude], dtype=np.float64) self._data_provider.update_sensor(tag, array, gnss_data.frame) def _parse_imu_cb(self, imu_data, tag): array = np.array([imu_data.accelerometer.x, imu_data.accelerometer.y, imu_data.accelerometer.z, imu_data.gyroscope.x, imu_data.gyroscope.y, imu_data.gyroscope.z, imu_data.compass, ], dtype=np.float64) self._data_provider.update_sensor(tag, array, imu_data.frame) def _parse_pseudosensor(self, package, tag): self._data_provider.update_sensor(tag, package.data, package.frame) class SensorInterface(object): def __init__(self): self._sensors_objects = {} self._data_buffers = {} self._new_data_buffers = Queue() self._queue_timeout = 10 # default: 10 # Only sensor that doesn't get the data on tick, needs special treatment self._opendrive_tag = None def register_sensor(self, tag, sensor_type, sensor): if tag in self._sensors_objects: raise SensorConfigurationInvalid("Duplicated sensor tag [{}]".format(tag)) self._sensors_objects[tag] = sensor if sensor_type == 'sensor.opendrive_map': self._opendrive_tag = tag def update_sensor(self, tag, data, timestamp): # print("Updating {} - {}".format(tag, timestamp)) if tag not in self._sensors_objects: raise SensorConfigurationInvalid("The sensor with tag [{}] has not been created!".format(tag)) self._new_data_buffers.put((tag, timestamp, data)) def get_data(self): try: data_dict = {} while len(data_dict.keys()) < len(self._sensors_objects.keys()): # Don't wait for the opendrive sensor if self._opendrive_tag and self._opendrive_tag not in data_dict.keys() \ and len(self._sensors_objects.keys()) == len(data_dict.keys()) + 1: # print("Ignoring opendrive sensor") break sensor_data = self._new_data_buffers.get(True, self._queue_timeout) data_dict[sensor_data[0]] = ((sensor_data[1], sensor_data[2])) except Empty: raise SensorReceivedNoData("A sensor took too long to send their data") return data_dict ================================================ FILE: leaderboard/leaderboard/leaderboard_evaluator.py ================================================ #!/usr/bin/env python # Copyright (c) 2018-2019 Intel Corporation. # authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com) # # This work is licensed under the terms of the MIT license. # For a copy, see . """ CARLA Challenge Evaluator Routes Provisional code to evaluate Autonomous Agents for the CARLA Autonomous Driving challenge """ from __future__ import print_function from multiprocessing.connection import wait import traceback import argparse from argparse import RawTextHelpFormatter from datetime import datetime from distutils.version import LooseVersion import importlib import os import sys import gc import pkg_resources import sys import carla import copy import signal import time import subprocess from srunner.scenariomanager.carla_data_provider import * from srunner.scenariomanager.timer import GameTime from srunner.scenariomanager.watchdog import Watchdog import random from leaderboard.scenarios.scenario_manager import ScenarioManager from leaderboard.scenarios.route_scenario import RouteScenario from leaderboard.envs.sensor_interface import SensorInterface, SensorConfigurationInvalid from leaderboard.autoagents.agent_wrapper import AgentWrapper, AgentError from leaderboard.utils.statistics_manager import StatisticsManager from leaderboard.utils.route_indexer import RouteIndexer def str2bool(v): if isinstance(v, bool): return v if v.lower() in ('yes', 'true', 't', 'y', '1'): return True elif v.lower() in ('no', 'false', 'f', 'n', '0'): return False else: raise argparse.ArgumentTypeError('Boolean value expected.') sensors_to_icons = { 'sensor.camera.rgb': 'carla_camera', 'sensor.camera.semantic_segmentation': 'carla_camera', 'sensor.camera.depth': 'carla_camera', 'sensor.lidar.ray_cast': 'carla_lidar', 'sensor.lidar.ray_cast_semantic': 'carla_lidar', 'sensor.other.radar': 'carla_radar', 'sensor.other.gnss': 'carla_gnss', 'sensor.other.imu': 'carla_imu', 'sensor.opendrive_map': 'carla_opendrive_map', 'sensor.speedometer': 'carla_speedometer' } WEATHERS = { 'ClearNoon': carla.WeatherParameters.ClearNoon, 'ClearSunset': carla.WeatherParameters.ClearSunset, 'CloudyNoon': carla.WeatherParameters.CloudyNoon, 'CloudySunset': carla.WeatherParameters.CloudySunset, 'WetNoon': carla.WeatherParameters.WetNoon, 'WetSunset': carla.WeatherParameters.WetSunset, 'MidRainyNoon': carla.WeatherParameters.MidRainyNoon, 'MidRainSunset': carla.WeatherParameters.MidRainSunset, 'WetCloudyNoon': carla.WeatherParameters.WetCloudyNoon, 'WetCloudySunset': carla.WeatherParameters.WetCloudySunset, 'HardRainNoon': carla.WeatherParameters.HardRainNoon, 'HardRainSunset': carla.WeatherParameters.HardRainSunset, 'SoftRainNoon': carla.WeatherParameters.SoftRainNoon, 'SoftRainSunset': carla.WeatherParameters.SoftRainSunset, } def kill_carla(): kill_process = subprocess.Popen('killall -9 -r CarlaUE4-Linux', shell=True) kill_process.wait() time.sleep(5) class LeaderboardEvaluator(object): """ document me! """ ego_vehicles = [] # Tunable parameters client_timeout = 10.0 # in seconds wait_for_world = 20.0 # in seconds frame_rate = 20.0 # in Hz def __init__(self, args, statistics_manager): """ Setup CARLA client and world Setup ScenarioManager """ self.statistics_manager = statistics_manager self.sensors = None self.sensor_icons = [] self._vehicle_lights = carla.VehicleLightState.Position | carla.VehicleLightState.LowBeam self.carla_path = os.environ["CARLA_ROOT"] # 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. cmd = 'DISPLAY= bash ' + os.path.join(self.carla_path, 'CarlaUE4.sh')+f' -opengl -carla-rpc-port={args.port} -nosound' print(cmd) wait_time = 10 server_process = subprocess.Popen(cmd, shell=True, preexec_fn=os.setsid) print("Process ID:", server_process.pid) time.sleep(wait_time) self.client = carla.Client(args.host, int(args.port)) if args.timeout: self.client_timeout = float(args.timeout) self.client.set_timeout(self.client_timeout) try: self.traffic_manager = self.client.get_trafficmanager(int(args.trafficManagerPort)) # self.traffic_manager = self.client.get_trafficmanager(8000) except Exception as e: print("traffic_manager fail to init", flush=True) print(e, flush=True) dist = pkg_resources.get_distribution("carla") # load agent 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(args.timeout, args.debug > 1) # Time control for summary purposes self._start_time = GameTime.get_time() self._end_time = None # Create the agent timer self._agent_watchdog = Watchdog(int(float(args.timeout))) signal.signal(signal.SIGINT, self._signal_handler) def _signal_handler(self, signum, frame): """ Terminate scenario ticking when receiving a signal interrupt """ if self._agent_watchdog and not self._agent_watchdog.get_status(): raise RuntimeError("Timeout: Agent took too long to setup") elif self.manager: self.manager.signal_handler(signum, frame) def __del__(self): """ Cleanup and delete actors, ScenarioManager and CARLA world """ self._cleanup() if hasattr(self, 'manager') and self.manager: del self.manager if hasattr(self, 'world') and self.world: del self.world def _cleanup(self): """ Remove and destroy all actors """ # Simulation still running and in synchronous mode? if self.manager and self.manager.get_running_status() \ and hasattr(self, 'world') and self.world: # Reset to asynchronous mode settings = self.world.get_settings() settings.synchronous_mode = False settings.fixed_delta_seconds = None self.world.apply_settings(settings) self.traffic_manager.set_synchronous_mode(False) if self.manager: self.manager.cleanup() CarlaDataProvider.cleanup() for i, _ in enumerate(self.ego_vehicles): if self.ego_vehicles[i]: self.ego_vehicles[i].destroy() self.ego_vehicles[i] = None self.ego_vehicles = [] if self._agent_watchdog: self._agent_watchdog.stop() if hasattr(self, 'agent_instance') and self.agent_instance: self.agent_instance.destroy() self.agent_instance = None if hasattr(self, 'statistics_manager') and self.statistics_manager: self.statistics_manager.scenario = None def _prepare_ego_vehicles(self, ego_vehicles, wait_for_ego_vehicles=False): """ Spawn or update the ego vehicles """ if not wait_for_ego_vehicles: for vehicle in ego_vehicles: self.ego_vehicles.append(CarlaDataProvider.request_new_actor(vehicle.model, vehicle.transform, vehicle.rolename, color=vehicle.color, vehicle_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) # sync state CarlaDataProvider.get_world().tick() def _load_and_wait_for_world(self, args, town, ego_vehicles=None): """ Load a new CARLA world and provide data to CarlaDataProvider """ self.traffic_manager.set_synchronous_mode(False) # if hasattr(self, 'world'): # settings = self.world.get_settings() # settings.synchronous_mode = False # self.world.apply_settings(settings) print(town) try: self.world = self.client.load_world(town) except Exception as e: print(111, e) settings = self.world.get_settings() settings.fixed_delta_seconds = 1.0 / self.frame_rate settings.synchronous_mode = True self.world.apply_settings(settings) self.world.reset_all_traffic_lights() CarlaDataProvider.set_client(self.client) CarlaDataProvider.set_world(self.world) CarlaDataProvider.set_traffic_manager_port(int(args.trafficManagerPort)) if args.weather != "none": assert args.weather in WEATHERS CarlaDataProvider.set_weather(WEATHERS[args.weather]) self.traffic_manager.set_synchronous_mode(True) if not os.environ['IS_EVAL']: args.trafficManagerSeed = random.randint(0, 100000) args.init_trafficManagerSeed = random.randint(0, 100000) print("Seed", args.trafficManagerSeed) self.traffic_manager.set_random_device_seed(int(args.trafficManagerSeed)) # Wait for the world to be ready if CarlaDataProvider.is_sync_mode(): self.world.tick() else: self.world.wait_for_tick() if CarlaDataProvider.get_map().name != town: raise Exception("The CARLA server uses the wrong map!" "This scenario requires to use map {}".format(town)) def _register_statistics(self, config, checkpoint, entry_status, crash_message=""): """ Computes and saved the simulation statistics """ # register statistics current_stats_record = self.statistics_manager.compute_route_statistics( config, self.manager.scenario_duration_system, self.manager.scenario_duration_game, crash_message ) print("\033[1m> Registering the route statistics\033[0m") self.statistics_manager.save_record(current_stats_record, config.index, checkpoint) self.statistics_manager.save_entry_status(entry_status, False, checkpoint) def _load_and_run_scenario(self, args, config): """ Load and run the scenario given by config. Depending on what code fails, the simulation will either stop the route and continue from the next one, or report a crash and stop. """ crash_message = "" entry_status = "Started" print("\n\033[1m========= Preparing {} (repetition {}) =========".format(config.name, config.repetition_index)) print("> Setting up the agent\033[0m") # Prepare the statistics of the route self.statistics_manager.set_route(config.name, config.index) # Set up the user's agent, and the timer to avoid freezing the simulation try: self._agent_watchdog.start() agent_class_name = getattr(self.module_agent, 'get_entry_point')() if "roach" not in args.agent_config: self.agent_instance = getattr(self.module_agent, agent_class_name)(args.agent_config + "+" + str(config.index) + "+" + str(config.repetition_index)) else: self.agent_instance = getattr(self.module_agent, agent_class_name)(args.agent_config) config.agent = self.agent_instance # Check and store the sensors if not self.sensors: self.sensors = self.agent_instance.sensors() track = self.agent_instance.track AgentWrapper.validate_sensor_configuration(self.sensors, track, args.track) self.sensor_icons = [sensors_to_icons[sensor['type']] for sensor in self.sensors] self.statistics_manager.save_sensors(self.sensor_icons, args.checkpoint) config.folder_name = self.agent_instance.folder_name self._agent_watchdog.stop() except SensorConfigurationInvalid as e: # The sensors are invalid -> set the ejecution to rejected and stop print("\n\033[91mThe sensor's configuration used is invalid:") print("> {}\033[0m\n".format(e)) traceback.print_exc() crash_message = "Agent's sensors were invalid" entry_status = "Rejected" self._register_statistics(config, args.checkpoint, entry_status, crash_message) self._cleanup() sys.exit(-1) except Exception as e: # The agent setup has failed -> start the next route print("\n\033[91mCould not set up the required agent:") print("> {}\033[0m\n".format(e)) traceback.print_exc() crash_message = "Agent couldn't be set up" self._register_statistics(config, args.checkpoint, entry_status, crash_message) self._cleanup() return print("\033[1m> Loading the world\033[0m") # Load the world and the scenario try: args.trafficManagerSeed = int(args.init_trafficManagerSeed) + int(config.index) self._load_and_wait_for_world(args, config.town, config.ego_vehicles) self._prepare_ego_vehicles(config.ego_vehicles, False) scenario = RouteScenario(world=self.world, config=config, debug_mode=args.debug) self.statistics_manager.set_scenario(scenario.scenario) # self.agent_instance._init() # self.agent_instance.sensor_interface = SensorInterface() #Night mode if config.weather.sun_altitude_angle < 0.0: for vehicle in scenario.ego_vehicles: vehicle.set_light_state(carla.VehicleLightState(self._vehicle_lights)) # Load scenario and run it if args.record: self.client.start_recorder("{}/{}_rep{}.log".format(args.record, config.name, config.repetition_index)) self.manager.load_scenario(scenario, self.agent_instance, config.repetition_index) except Exception as e: # The scenario is wrong -> set the ejecution to crashed and stop print("\n\033[91mThe scenario could not be loaded:") print("> {}\033[0m\n".format(e)) traceback.print_exc() crash_message = "Simulation crashed" entry_status = "Crashed" self._register_statistics(config, args.checkpoint, entry_status, crash_message) if args.record: self.client.stop_recorder() self._cleanup() sys.exit(-1) print("\033[1m> Running the route\033[0m") # Run the scenario self.manager.run_scenario() try: print("\033[1m> Stopping the route\033[0m") self.manager.stop_scenario() self._register_statistics(config, args.checkpoint, entry_status, crash_message) if args.record: self.client.stop_recorder() # Remove all actors scenario.remove_all_actors() self._cleanup() except Exception as e: print("\n\033[91mFailed to stop the scenario, the statistics might be empty:") print("> {}\033[0m\n".format(e)) traceback.print_exc() crash_message = "Simulation crashed" if crash_message == "Simulation crashed": sys.exit(-1) def run(self, args): """ Run the challenge mode """ # agent_class_name = getattr(self.module_agent, 'get_entry_point')() # self.agent_instance = getattr(self.module_agent, agent_class_name)(args.agent_config) route_indexer = RouteIndexer(args.routes, args.scenarios, args.repetitions) print("resume:", args.resume, flush=True) if args.resume: route_indexer.resume(args.checkpoint) self.statistics_manager.resume(args.checkpoint) else: self.statistics_manager.clear_record(args.checkpoint) route_indexer.save_state(args.checkpoint) while route_indexer.peek(): # setup config = route_indexer.next() # run self._load_and_run_scenario(args, config) for obj in gc.get_objects(): try: if torch.is_tensor(obj) or (hasattr(obj, 'data') and torch.is_tensor(obj.data)): print(type(obj), obj.size()) except: pass route_indexer.save_state(args.checkpoint) # save global statistics print("\033[1m> Registering the global statistics\033[0m") global_stats_record = self.statistics_manager.compute_global_statistics(route_indexer.total) StatisticsManager.save_global_record(global_stats_record, self.sensor_icons, route_indexer.total, args.checkpoint) def main(): description = "CARLA AD Leaderboard Evaluation: evaluate your Agent in CARLA scenarios\n" # general parameters parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter) parser.add_argument('--host', default='localhost', 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('--trafficManagerPort', default='8000', help='Port to use for the TrafficManager (default: 8000)') parser.add_argument('--trafficManagerSeed', default='2023', help='Seed used by the TrafficManager (default: 0)') parser.add_argument('--init_trafficManagerSeed', default=2023, type=int) parser.add_argument('--debug', type=int, help='Run with debug output', default=0) parser.add_argument('--record', type=str, default='', help='Use CARLA recording feature to create a recording of the scenario') parser.add_argument('--timeout', default="6000.0", help='Set the CARLA client timeout value in seconds') # simulation setup parser.add_argument('--routes', help='Name of the route to be executed. Point to the route_xml_file to be executed.', required=True) parser.add_argument('--weather', type=str, default='none', help='Name of the weahter to be executed', ) parser.add_argument('--scenarios', help='Name of the scenario annotation file to be mixed with the route.', required=True) parser.add_argument('--repetitions', type=int, default=1, help='Number of repetitions per route.') # agent-related options parser.add_argument("-a", "--agent", type=str, help="Path to Agent's py file to evaluate", required=True) parser.add_argument("--agent-config", type=str, help="Path to Agent's configuration file", default="") parser.add_argument("--track", type=str, default='SENSORS', help="Participation track: SENSORS, MAP") parser.add_argument('--resume', type=str2bool, default=False, help='Resume execution from last checkpoint?') parser.add_argument('--is_local', type=str2bool, default=False, help='whether in local machine') parser.add_argument('--is_eval', type=str2bool, default=False, help='whether in eval mode otherwise data collection mode') parser.add_argument("--checkpoint", type=str, default='./simulation_results.json', help="Path to checkpoint used for saving statistics and resuming") arguments = parser.parse_args() print("init statistics_manager") statistics_manager = StatisticsManager() if arguments.is_eval: os.environ['IS_EVAL'] = "True" else: os.environ['IS_EVAL'] = "False" if arguments.is_local: os.environ['IS_LOCAL'] = "True" else: os.environ['IS_LOCAL'] = "False" try: print("begin") leaderboard_evaluator = LeaderboardEvaluator(arguments, statistics_manager) leaderboard_evaluator.run(arguments) except Exception as e: traceback.print_exc() finally: print("Collect Done", flush=True) del leaderboard_evaluator if __name__ == '__main__': main() ================================================ FILE: leaderboard/leaderboard/scenarios/__init__.py ================================================ ================================================ FILE: leaderboard/leaderboard/scenarios/background_activity.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Scenario spawning elements to make the town dynamic and interesting """ import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenarios.basic_scenario import BasicScenario import os BACKGROUND_ACTIVITY_SCENARIOS = ["BackgroundActivity"] class BackgroundActivity(BasicScenario): """ Implementation of a scenario to spawn a set of background actors, and to remove traffic jams in background traffic This is a single ego vehicle scenario """ category = "BackgroundActivity" town_amount = { # 'Town01': 120, 'Town01': 120, 'Town02': 100, 'Town03': 120, 'Town04': 200, 'Town05': 120, 'Town06': 150, 'Town07': 110, 'Town08': 180, 'Town09': 300, 'Town10': 120, } def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, timeout=35 * 60): """ Setup all relevant parameters and create scenario """ self.config = config self.debug = debug_mode self.timeout = timeout # Timeout of scenario in seconds super(BackgroundActivity, self).__init__("BackgroundActivity", ego_vehicles, config, world, debug_mode, terminate_on_failure=True, criteria_enable=True) def _initialize_actors(self, config): town_name = config.town if town_name in self.town_amount: amount = self.town_amount[town_name] else: amount = 0 if os.environ["BENCHMARK"] == "town05long": amount = 120 print("----------------Eval with Town05 Long, amount=120", flush=True) if os.environ["BENCHMARK"] == "longest6": amount = 500 print("----------------Eval with Longest6, amount=500", flush=True) new_actors = CarlaDataProvider.request_new_batch_actors('vehicle.*', amount, carla.Transform(), autopilot=True, random_location=True, rolename='background') if new_actors is None: raise Exception("Error: Unable to add the background activity, all spawn points were occupied") for _actor in new_actors: self.other_actors.append(_actor) def _create_behavior(self): """ Basic behavior do nothing, i.e. Idle """ pass def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ pass def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: leaderboard/leaderboard/scenarios/master_scenario.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Basic CARLA Autonomous Driving training scenario """ import py_trees from srunner.scenarioconfigs.route_scenario_configuration import RouteConfiguration from srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, InRouteTest, RouteCompletionTest, RunningRedLightTest, RunningStopTest, OutsideRouteLanesTest) from srunner.scenarios.basic_scenario import BasicScenario from leaderboard.scenarios.scenarioatomics.atomic_criteria import ActorSpeedAboveThresholdTest MASTER_SCENARIO = ["MasterScenario"] class MasterScenario(BasicScenario): """ Implementation of a Master scenario that controls the route. This is a single ego vehicle scenario """ category = "Master" radius = 10.0 # meters def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=300): """ Setup all relevant parameters and create scenario """ self.config = config self.route = None # Timeout of scenario in seconds self.timeout = timeout if hasattr(self.config, 'route'): self.route = self.config.route else: raise ValueError("Master scenario must have a route") super(MasterScenario, self).__init__("MasterScenario", ego_vehicles=ego_vehicles, config=config, world=world, debug_mode=debug_mode, terminate_on_failure=True, criteria_enable=criteria_enable) def _create_behavior(self): """ Basic behavior do nothing, i.e. Idle """ # Build behavior tree sequence = py_trees.composites.Sequence("MasterScenario") idle_behavior = Idle() sequence.add_child(idle_behavior) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ if isinstance(self.route, RouteConfiguration): route = self.route.data else: route = 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) parallel_criteria = py_trees.composites.Parallel("group_criteria", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) parallel_criteria.add_child(completion_criterion) parallel_criteria.add_child(collision_criterion) parallel_criteria.add_child(route_criterion) parallel_criteria.add_child(outsidelane_criterion) parallel_criteria.add_child(red_light_criterion) parallel_criteria.add_child(stop_criterion) parallel_criteria.add_child(blocked_criterion) return parallel_criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: leaderboard/leaderboard/scenarios/route_scenario.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 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 xml.etree.ElementTree as ET import numpy.random as random import py_trees import carla from agents.navigation.local_planner import RoadOption # pylint: disable=line-too-long from srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData # pylint: enable=line-too-long from srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle, ScenarioTriggerer from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenarios.basic_scenario import BasicScenario from srunner.scenarios.control_loss import ControlLoss from srunner.scenarios.follow_leading_vehicle import FollowLeadingVehicle 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 SignalJunctionCrossingRoute, NoSignalJunctionCrossingRoute from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, InRouteTest, RouteCompletionTest, OutsideRouteLanesTest, RunningRedLightTest, RunningStopTest, ActorSpeedAboveThresholdTest) from leaderboard.utils.route_parser import RouteParser, TRIGGER_THRESHOLD, TRIGGER_ANGLE_THRESHOLD from leaderboard.utils.route_manipulation import interpolate_trajectory import os ROUTESCENARIO = ["RouteScenario"] SECONDS_GIVEN_PER_METERS = 0.8 # for timeout # SECONDS_GIVEN_PER_METERS = 2 # for timeout INITIAL_SECONDS_DELAY = 5.0 NUMBER_CLASS_TRANSLATION = { "Scenario1": ControlLoss, "Scenario2": FollowLeadingVehicle, "Scenario3": DynamicObjectCrossing, "Scenario4": VehicleTurningRoute, "Scenario5": OtherLeadingVehicle, "Scenario6": ManeuverOppositeDirection, "Scenario7": SignalJunctionCrossingRoute, "Scenario8": SignalJunctionCrossingRoute, "Scenario9": SignalJunctionCrossingRoute, "Scenario10": NoSignalJunctionCrossingRoute } def oneshot_behavior(name, variable_name, behaviour): """ This is taken from py_trees.idiom.oneshot. """ # Initialize the variables blackboard = py_trees.blackboard.Blackboard() _ = blackboard.set(variable_name, False) # Wait until the scenario has ended subtree_root = py_trees.composites.Selector(name=name) check_flag = py_trees.blackboard.CheckBlackboardVariable( name=variable_name + " Done?", variable_name=variable_name, expected_value=True, clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE ) set_flag = py_trees.blackboard.SetBlackboardVariable( name="Mark Done", variable_name=variable_name, variable_value=True ) # If it's a sequence, don't double-nest it in a redundant manner if isinstance(behaviour, py_trees.composites.Sequence): behaviour.add_child(set_flag) sequence = behaviour else: sequence = py_trees.composites.Sequence(name="OneShot") sequence.add_children([behaviour, set_flag]) subtree_root.add_children([check_flag, sequence]) return subtree_root 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 """ category = "RouteScenario" def __init__(self, world, config, debug_mode=0, criteria_enable=True): """ 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>0) ego_vehicle = self._update_ego_vehicle() self.list_scenarios = self._build_scenario_instances(world, ego_vehicle, self.sampled_scenarios_definitions, scenarios_per_tick=10, timeout=self.timeout, debug_mode=debug_mode>1) self.is_eval = (os.environ['IS_EVAL'] == "True") print("IS_EVAL", self.is_eval) super(RouteScenario, self).__init__(name=config.name, ego_vehicles=[ego_vehicle], config=config, world=world, debug_mode=debug_mode>1, 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(world, config.trajectory) gps_route, route, wp_route = interpolate_trajectory(world, 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)) config.agent.set_global_plan(gps_route, self.route, wp_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=1.0, persistency=50000.0) 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') spectator = CarlaDataProvider.get_world().get_spectator() ego_trans = ego_vehicle.get_transform() spectator.set_transform(carla.Transform(ego_trans.location + carla.Location(z=50), carla.Rotation(pitch=-90))) 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 + INITIAL_SECONDS_DELAY) # 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) size = 0.2 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 size = 0.1 world.debug.draw_point(wp, size=size, 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 _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 rgn = random.RandomState(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 # def select_scenario(list_scenarios): # # priority to the scenarios with higher number: 10 has priority over 9, etc. # higher_id = -1 # selected_scenario = None # for scenario in list_scenarios: # try: # scenario_number = int(scenario['name'].split('Scenario')[1]) # except: # scenario_number = -1 # if scenario_number >= higher_id: # higher_id = scenario_number # selected_scenario = scenario # return selected_scenario def select_scenario(list_scenarios): # priority to the scenarios with higher number: 10 has priority over 9, etc. selected_scenario = None for scenario in list_scenarios: try: scenario_number = int(scenario['name'].split('Scenario')[1]) except: scenario_number = -1 if scenario_number == 3: selected_scenario = scenario break if selected_scenario is None: return rgn.choice(list_scenarios) return selected_scenario def select_scenario_randomly(list_scenarios): # randomly select a scenario return rgn.choice(list_scenarios) # The idea is to randomly sample a scenario per trigger position. self.is_eval = (os.environ['IS_EVAL'] == "True") print("IS_EVAL", self.is_eval) sampled_scenarios = [] for trigger in potential_scenarios_definitions.keys(): possible_scenarios = potential_scenarios_definitions[trigger] if self.is_eval: scenario_choice = select_scenario(possible_scenarios) # original prioritized sampling else: scenario_choice = select_scenario_randomly(possible_scenarios) # random sampling 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 = rgn.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('vehicle.lincoln.mkz2017', 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() except Exception as e: 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 #TODO: tune to have some vehicle town_amount = { 'Town01': 120, 'Town02': 100, 'Town03': 120, 'Town04': 200, 'Town05': 120, 'Town06': 150, 'Town07': 110, 'Town08': 180, 'Town09': 300, 'Town10HD': 120, # town10 doesn't load properly for some reason } amount = town_amount[config.town] if config.town in town_amount else 0 if os.environ["BENCHMARK"] == "town05long": amount = 120 print("----------------Eval with Town05 Long, amount=120", flush=True) if os.environ["BENCHMARK"] == "longest6": amount = 500 print("----------------Eval with Longest6, amount=500", flush=True) new_actors = CarlaDataProvider.request_new_batch_actors('vehicle.*', amount, carla.Transform(), autopilot=True, random_location=True, rolename='background') if new_actors is None: raise Exception("Error: Unable to add the background activity, all spawn points were occupied") 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=name, variable_name=name, behaviour=scenario.scenario.behavior) 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=(not self.is_eval)) 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], terminate_on_failure=(not self.is_eval)) 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, name="AgentBlockedTest") criteria.append(completion_criterion) criteria.append(outsidelane_criterion) criteria.append(collision_criterion) criteria.append(red_light_criterion) criteria.append(stop_criterion) criteria.append(route_criterion) criteria.append(blocked_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: leaderboard/leaderboard/scenarios/scenario_manager.py ================================================ #!/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 implementations. It must not be modified and is for reference only! """ from __future__ import print_function import signal import sys import time import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import GameTime from srunner.scenariomanager.watchdog import Watchdog from leaderboard.autoagents.agent_wrapper import AgentWrapper, AgentError from leaderboard.envs.sensor_interface import SensorReceivedNoData from leaderboard.utils.result_writer import ResultOutputProvider class ScenarioManager(object): """ Basic scenario manager class. This class holds all functionality required to start, run and stop 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. If needed, cleanup with manager.stop_scenario() """ def __init__(self, timeout, debug_mode=False): """ 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._running = False self._timestamp_last_run = 0.0 self._timeout = float(timeout) # Used to detect if the simulation is down watchdog_timeout = max(5, self._timeout - 2) self._watchdog = Watchdog(watchdog_timeout) # Avoid the agent from freezing the simulation agent_timeout = watchdog_timeout - 1 self._agent_watchdog = Watchdog(agent_timeout) self.scenario_duration_system = 0.0 self.scenario_duration_game = 0.0 self.start_system_time = None self.end_system_time = None self.end_game_time = None # Register the scenario tick as callback for the CARLA world # Use the callback_id inside the signal handler to allow external interrupts signal.signal(signal.SIGINT, self.signal_handler) def signal_handler(self, signum, frame): """ Terminate scenario ticking when receiving a signal interrupt """ self._running = False def cleanup(self): """ Reset all parameters """ 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.end_game_time = None def load_scenario(self, scenario, agent, rep_number): """ Load a new scenario """ GameTime.restart() self._agent = AgentWrapper(agent) 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 self.repetition_number = rep_number # To print the scenario tree uncomment the next line # py_trees.display.render_dot_tree(self.scenario_tree) CarlaDataProvider.set_ego(self.ego_vehicles[0]) self._agent.setup_sensors(self.ego_vehicles[0], self._debug_mode) def run_scenario(self): """ Trigger the start of the scenario and wait for it to finish/fail """ self.start_system_time = time.time() self.start_game_time = GameTime.get_time() self._watchdog.start() self._running = True while self._running: timestamp = None world = CarlaDataProvider.get_world() CarlaDataProvider.set_time_step((GameTime.get_time()-self.start_game_time)*20) #20Hz if world: snapshot = world.get_snapshot() if snapshot: timestamp = snapshot.timestamp if timestamp: self._tick_scenario(timestamp) def _tick_scenario(self, timestamp): """ Run next tick of scenario and the agent and tick the world. """ if self._timestamp_last_run < timestamp.elapsed_seconds and self._running: self._timestamp_last_run = timestamp.elapsed_seconds self._watchdog.update() # Update game time and actor information GameTime.on_carla_tick(timestamp) CarlaDataProvider.on_carla_tick() try: ego_action = self._agent() # Special exception inside the agent that isn't caused by the agent except SensorReceivedNoData as e: raise RuntimeError(e) except Exception as e: raise AgentError(e) 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 spectator = CarlaDataProvider.get_world().get_spectator() ego_trans = self.ego_vehicles[0].get_transform() spectator.set_transform(carla.Transform(ego_trans.location + carla.Location(z=50), carla.Rotation(pitch=-90))) if self._running and self.get_running_status(): CarlaDataProvider.get_world().tick(self._timeout) 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 triggers a proper termination of a scenario """ self._watchdog.stop() self.end_system_time = time.time() self.end_game_time = GameTime.get_time() self.scenario_duration_system = self.end_system_time - self.start_system_time self.scenario_duration_game = self.end_game_time - self.start_game_time if self.get_running_status(): if self.scenario is not None: self.scenario.terminate() if self._agent is not None: self._agent.cleanup() self._agent = None self.analyze_scenario() def analyze_scenario(self): """ Analyzes and prints the results of the route """ global_result = '\033[92m'+'SUCCESS'+'\033[0m' for criterion in self.scenario.get_criteria(): if criterion.test_status != "SUCCESS": global_result = '\033[91m'+'FAILURE'+'\033[0m' if self.scenario.timeout_node.timeout: global_result = '\033[91m'+'FAILURE'+'\033[0m' ResultOutputProvider(self, global_result) ================================================ FILE: leaderboard/leaderboard/scenarios/scenarioatomics/__init__.py ================================================ ================================================ FILE: leaderboard/leaderboard/scenarios/scenarioatomics/atomic_criteria.py ================================================ #!/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 additional atomic evaluation criteria required to analyze if a scenario was completed successfully or failed. Criteria should run continuously to monitor the state of a single actor, multiple actors or environmental parameters. Hence, a termination is not required. The atomic criteria are implemented with py_trees. """ import py_trees from srunner.scenariomanager.timer import GameTime from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_criteria import Criterion from srunner.scenariomanager.traffic_events import TrafficEvent, TrafficEventType class ActorSpeedAboveThresholdTest(Criterion): """ This test will fail if the actor has had its linear velocity lower than a specific value for a specific amount of time Important parameters: - actor: CARLA actor to be used for this test - speed_threshold: speed required - below_threshold_max_time: Maximum time (in seconds) the actor can remain under the speed threshold - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ def __init__(self, actor, speed_threshold, below_threshold_max_time, name="ActorSpeedAboveThresholdTest", terminate_on_failure=False): """ Class constructor. """ super(ActorSpeedAboveThresholdTest, self).__init__(name, actor, 0, terminate_on_failure=terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._speed_threshold = speed_threshold self._below_threshold_max_time = below_threshold_max_time self._time_last_valid_state = None def update(self): """ Check if the actor speed is above the speed_threshold """ new_status = py_trees.common.Status.RUNNING linear_speed = CarlaDataProvider.get_velocity(self._actor) if linear_speed is not None: if linear_speed < self._speed_threshold and self._time_last_valid_state: if (GameTime.get_time() - self._time_last_valid_state) > self._below_threshold_max_time: # Game over. The actor has been "blocked" for too long self.test_status = "FAILURE" # record event vehicle_location = CarlaDataProvider.get_location(self._actor) blocked_event = TrafficEvent(event_type=TrafficEventType.VEHICLE_BLOCKED) ActorSpeedAboveThresholdTest._set_event_message(blocked_event, vehicle_location) ActorSpeedAboveThresholdTest._set_event_dict(blocked_event, vehicle_location) self.list_traffic_events.append(blocked_event) else: self._time_last_valid_state = GameTime.get_time() if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status @staticmethod def _set_event_message(event, location): """ Sets the message of the event """ event.set_message('Agent got blocked at (x={}, y={}, z={})'.format(round(location.x, 3), round(location.y, 3), round(location.z, 3))) @staticmethod def _set_event_dict(event, location): """ Sets the dictionary of the event """ event.set_dict({ 'x': location.x, 'y': location.y, 'z': location.z, }) ================================================ FILE: leaderboard/leaderboard/utils/__init__.py ================================================ ================================================ FILE: leaderboard/leaderboard/utils/checkpoint_tools.py ================================================ import json try: import simplejson as json except ImportError: import json import requests import os.path def autodetect_proxy(): proxies = {} proxy_https = os.getenv('HTTPS_PROXY', os.getenv('https_proxy', None)) proxy_http = os.getenv('HTTP_PROXY', os.getenv('http_proxy', None)) if proxy_https: proxies['https'] = proxy_https if proxy_http: proxies['http'] = proxy_http return proxies def fetch_dict(endpoint): data = None if endpoint.startswith(('http:', 'https:', 'ftp:')): proxies = autodetect_proxy() if proxies: response = requests.get(url=endpoint, proxies=proxies) else: response = requests.get(url=endpoint) try: data = response.json() except json.decoder.JSONDecodeError: data = {} else: data = {} if os.path.exists(endpoint): with open(endpoint) as fd: try: data = json.load(fd) except json.JSONDecodeError: data = {} return data def create_default_json_msg(): msg = { "sensors": [], "values": [], "labels": [], "entry_status": "", "eligible": "", "_checkpoint": { "progress": [], "records": [], "global_record": {} }, } return msg def save_dict(endpoint, data): if endpoint.startswith(('http:', 'https:', 'ftp:')): proxies = autodetect_proxy() if proxies: _ = requests.patch(url=endpoint, headers={'content-type':'application/json'}, data=json.dumps(data, indent=4, sort_keys=True), proxies=proxies) else: _ = requests.patch(url=endpoint, headers={'content-type':'application/json'}, data=json.dumps(data, indent=4, sort_keys=True)) else: with open(endpoint, 'w') as fd: json.dump(data, fd, indent=4, sort_keys=True) ================================================ FILE: leaderboard/leaderboard/utils/result_writer.py ================================================ #!/usr/bin/env python # Copyright (c) 2018-2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains the result gatherer and write for CARLA scenarios. It shall be used from the ScenarioManager only. """ from __future__ import print_function import time from tabulate import tabulate class ResultOutputProvider(object): """ This module contains the _result gatherer and write for CARLA scenarios. It shall be used from the ScenarioManager only. """ def __init__(self, data, global_result): """ - data contains all scenario-related information - global_result is overall pass/fail info """ self._data = data self._global_result = global_result self._start_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.start_system_time)) self._end_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.end_system_time)) print(self.create_output_text()) def create_output_text(self): """ Creates the output message """ # Create the title output = "\n" output += "\033[1m========= Results of {} (repetition {}) ------ {} \033[1m=========\033[0m\n".format( self._data.scenario_tree.name, self._data.repetition_number, self._global_result) output += "\n" # Simulation part system_time = round(self._data.scenario_duration_system, 2) game_time = round(self._data.scenario_duration_game, 2) ratio = round(self._data.scenario_duration_game / self._data.scenario_duration_system, 3) list_statistics = [["Start Time", "{}".format(self._start_time)]] list_statistics.extend([["End Time", "{}".format(self._end_time)]]) list_statistics.extend([["Duration (System Time)", "{}s".format(system_time)]]) list_statistics.extend([["Duration (Game Time)", "{}s".format(game_time)]]) list_statistics.extend([["Ratio (System Time / Game Time)", "{}".format(ratio)]]) output += tabulate(list_statistics, tablefmt='fancy_grid') output += "\n\n" # Criteria part header = ['Criterion', 'Result', 'Value'] list_statistics = [header] for criterion in self._data.scenario.get_criteria(): actual_value = criterion.actual_value expected_value = criterion.expected_value_success name = criterion.name result = criterion.test_status if result == "SUCCESS": result = '\033[92m'+'SUCCESS'+'\033[0m' elif result == "FAILURE": result = '\033[91m'+'FAILURE'+'\033[0m' if name == "RouteCompletionTest": actual_value = str(actual_value) + " %" elif name == "OutsideRouteLanesTest": actual_value = str(actual_value) + " %" elif name == "CollisionTest": actual_value = str(actual_value) + " times" elif name == "RunningRedLightTest": actual_value = str(actual_value) + " times" elif name == "RunningStopTest": actual_value = str(actual_value) + " times" elif name == "InRouteTest": actual_value = "" elif name == "AgentBlockedTest": actual_value = "" list_statistics.extend([[name, result, actual_value]]) # Timeout name = "Timeout" actual_value = self._data.scenario_duration_game expected_value = self._data.scenario.timeout if self._data.scenario_duration_game < self._data.scenario.timeout: result = '\033[92m'+'SUCCESS'+'\033[0m' else: result = '\033[91m'+'FAILURE'+'\033[0m' list_statistics.extend([[name, result, '']]) output += tabulate(list_statistics, tablefmt='fancy_grid') output += "\n" return output ================================================ FILE: leaderboard/leaderboard/utils/route_indexer.py ================================================ from collections import OrderedDict from dictor import dictor import copy from srunner.scenarioconfigs.route_scenario_configuration import RouteScenarioConfiguration from leaderboard.utils.route_parser import RouteParser from leaderboard.utils.checkpoint_tools import fetch_dict, create_default_json_msg, save_dict class RouteIndexer(): def __init__(self, routes_file, scenarios_file, repetitions): self._routes_file = routes_file self._scenarios_file = scenarios_file self._repetitions = repetitions self._configs_dict = OrderedDict() self._configs_list = [] self.routes_length = [] self._index = 0 # retrieve routes route_configurations = RouteParser.parse_routes_file(self._routes_file, self._scenarios_file, False) self.n_routes = len(route_configurations) self.total = self.n_routes*self._repetitions for i, config in enumerate(route_configurations): for repetition in range(repetitions): config.index = i * self._repetitions + repetition config.repetition_index = repetition self._configs_dict['{}.{}'.format(config.name, repetition)] = copy.copy(config) self._configs_list = list(self._configs_dict.items()) def peek(self): return not (self._index >= len(self._configs_list)) def next(self): if self._index >= len(self._configs_list): return None key, config = self._configs_list[self._index] self._index += 1 return config def resume(self, endpoint): data = fetch_dict(endpoint) if data: checkpoint_dict = dictor(data, '_checkpoint') if checkpoint_dict and 'progress' in checkpoint_dict: progress = checkpoint_dict['progress'] if not progress: current_route = 0 else: current_route, total_routes = progress if current_route <= self.total: self._index = current_route else: print('Problem reading checkpoint. Route id {} ' 'larger than maximum number of routes {}'.format(current_route, self.total)) def save_state(self, endpoint): data = fetch_dict(endpoint) if not data: data = create_default_json_msg() data['_checkpoint']['progress'] = [self._index, self.total] save_dict(endpoint, data) ================================================ FILE: leaderboard/leaderboard/utils/route_manipulation.py ================================================ #!/usr/bin/env python # Copyright (c) 2018-2019 Intel Labs. # authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com) # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Module to manipulate the routes, by making then more or less dense (Up to a certain parameter). It also contains functions to convert the CARLA world location do GPS coordinates. """ import math import xml.etree.ElementTree as ET from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO from agents.navigation.local_planner import RoadOption def _location_to_gps(lat_ref, lon_ref, location): """ Convert from world coordinates to GPS coordinates :param lat_ref: latitude reference for the current map :param lon_ref: longitude reference for the current map :param location: location to translate :return: dictionary with lat, lon and height """ EARTH_RADIUS_EQUA = 6378137.0 # pylint: disable=invalid-name scale = math.cos(lat_ref * math.pi / 180.0) mx = scale * lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0 my = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + lat_ref) * math.pi / 360.0)) mx += location.x my -= location.y lon = mx * 180.0 / (math.pi * EARTH_RADIUS_EQUA * scale) lat = 360.0 * math.atan(math.exp(my / (EARTH_RADIUS_EQUA * scale))) / math.pi - 90.0 z = location.z return {'lat': lat, 'lon': lon, 'z': z} def location_route_to_gps(route, lat_ref, lon_ref): """ Locate each waypoint of the route into gps, (lat long ) representations. :param route: :param lat_ref: :param lon_ref: :return: """ gps_route = [] for transform, connection in route: gps_point = _location_to_gps(lat_ref, lon_ref, transform.location) gps_route.append((gps_point, connection)) return gps_route def _get_latlon_ref(world): """ Convert from waypoints world coordinates to CARLA GPS coordinates :return: tuple with lat and lon coordinates """ xodr = world.get_map().to_opendrive() tree = ET.ElementTree(ET.fromstring(xodr)) # default reference lat_ref = 42.0 lon_ref = 2.0 for opendrive in tree.iter("OpenDRIVE"): for header in opendrive.iter("header"): for georef in header.iter("geoReference"): if georef.text: str_list = georef.text.split(' ') for item in str_list: if '+lat_0' in item: lat_ref = float(item.split('=')[1]) if '+lon_0' in item: lon_ref = float(item.split('=')[1]) return lat_ref, lon_ref def downsample_route(route, sample_factor): """ Downsample the route by some factor. :param route: the trajectory , has to contain the waypoints and the road options :param sample_factor: Maximum distance between samples :return: returns the ids of the final route that can """ ids_to_sample = [] prev_option = None dist = 0 for i, point in enumerate(route): curr_option = point[1] # Lane changing if curr_option in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT): ids_to_sample.append(i) dist = 0 # When road option changes elif prev_option != curr_option and prev_option not in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT): ids_to_sample.append(i) dist = 0 # After a certain max distance elif dist > sample_factor: ids_to_sample.append(i) dist = 0 # At the end elif i == len(route) - 1: ids_to_sample.append(i) dist = 0 # Compute the distance traveled else: curr_location = point[0].location prev_location = route[i-1][0].location dist += curr_location.distance(prev_location) prev_option = curr_option return ids_to_sample def interpolate_trajectory(world, waypoints_trajectory, hop_resolution=1.0): """ Given some raw keypoints interpolate a full dense trajectory to be used by the user. returns the full interpolated route both in GPS coordinates and also in its original form. Args: - world: an reference to the CARLA world so we can use the planner - waypoints_trajectory: the current coarse trajectory - hop_resolution: is the resolution, how dense is the provided trajectory going to be made """ dao = GlobalRoutePlannerDAO(world.get_map(), hop_resolution) grp = GlobalRoutePlanner(dao) grp.setup() # Obtain route plan route = [] wp_route = [] for i in range(len(waypoints_trajectory) - 1): # Goes until the one before the last. waypoint = waypoints_trajectory[i] waypoint_next = waypoints_trajectory[i + 1] interpolated_trace = grp.trace_route(waypoint, waypoint_next) for wp_tuple in interpolated_trace: route.append((wp_tuple[0].transform, wp_tuple[1])) wp_route.append((wp_tuple[0], wp_tuple[1])) lat_ref, lon_ref = _get_latlon_ref(world) return location_route_to_gps(route, lat_ref, lon_ref), route, wp_route ================================================ FILE: leaderboard/leaderboard/utils/route_parser.py ================================================ #!/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. """ from collections import OrderedDict 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 # 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. # for loading predefined weathers while parsing routes WEATHERS = { '1': carla.WeatherParameters.ClearNoon, '2': carla.WeatherParameters.ClearSunset, '3': carla.WeatherParameters.CloudyNoon, '4': carla.WeatherParameters.CloudySunset, '5': carla.WeatherParameters.WetNoon, '6': carla.WeatherParameters.WetSunset, '7': carla.WeatherParameters.MidRainyNoon, '8': carla.WeatherParameters.MidRainSunset, '9': carla.WeatherParameters.WetCloudyNoon, '10': carla.WeatherParameters.WetCloudySunset, '11': carla.WeatherParameters.HardRainNoon, '12': carla.WeatherParameters.HardRainSunset, '13': carla.WeatherParameters.SoftRainNoon, '14': carla.WeatherParameters.SoftRainSunset, } 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') as f: annotation_dict = json.loads(f.read(), object_pairs_hook=OrderedDict) final_dict = OrderedDict() 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) # default: parse_weather(route) new_config.scenario_file = scenario_file 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, cloudiness=30) 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']) if 'fog_falloff' in weather_attrib.attrib: weather.fog_falloff = float(weather_attrib.attrib['fog_falloff']) return weather @staticmethod def parse_preset_weather(route): """ Returns one of the 14 preset weather condition. If the route has no weather attribute, the default one is triggered. """ if 'weather' not in route.attrib: weather = carla.WeatherParameters(sun_altitude_angle=70, cloudiness=30) else: weather = WEATHERS[route.attrib['weather']] return weather @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 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 # 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.LEFT == tuple_wp_turn[1]: subtype = 'S7left' elif RoadOption.RIGHT == tuple_wp_turn[1]: subtype = 'S7right' elif 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 = OrderedDict() # We have a table of IDs and trigger positions associated possible_scenarios = OrderedDict() # 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 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 configurations } 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 ================================================ FILE: leaderboard/leaderboard/utils/statistics_manager.py ================================================ #!/usr/bin/env python # Copyright (c) 2018-2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains a statistics manager for the CARLA AD leaderboard """ from __future__ import print_function from dictor import dictor import math import sys from srunner.scenariomanager.traffic_events import TrafficEventType from leaderboard.utils.checkpoint_tools import fetch_dict, save_dict, create_default_json_msg PENALTY_COLLISION_PEDESTRIAN = 0.50 PENALTY_COLLISION_VEHICLE = 0.60 PENALTY_COLLISION_STATIC = 0.65 PENALTY_TRAFFIC_LIGHT = 0.70 PENALTY_STOP = 0.80 import os if os.environ["BENCHMARK"] == "longest6": PENALTY_STOP = 1.0 print("----------------Eval with Longest6, PENALTY_STOP=1.0") class RouteRecord(): def __init__(self): self.route_id = None self.index = None self.status = 'Started' self.infractions = { 'collisions_pedestrian': [], 'collisions_vehicle': [], 'collisions_layout': [], 'red_light': [], 'stop_infraction': [], 'outside_route_lanes': [], 'route_dev': [], 'route_timeout': [], 'vehicle_blocked': [] } self.scores = { 'score_route': 0, 'score_penalty': 0, 'score_composed': 0 } self.meta = {} def to_route_record(record_dict): record = RouteRecord() for key, value in record_dict.items(): setattr(record, key, value) return record def compute_route_length(config): trajectory = config.trajectory route_length = 0.0 previous_location = None for location in trajectory: if previous_location: dist = math.sqrt((location.x-previous_location.x)*(location.x-previous_location.x) + (location.y-previous_location.y)*(location.y-previous_location.y) + (location.z - previous_location.z) * (location.z - previous_location.z)) route_length += dist previous_location = location return route_length class StatisticsManager(object): """ This is the statistics manager for the CARLA leaderboard. It gathers data at runtime via the scenario evaluation criteria. """ def __init__(self): self._master_scenario = None self._registry_route_records = [] def resume(self, endpoint): data = fetch_dict(endpoint) if data and dictor(data, '_checkpoint.records'): records = data['_checkpoint']['records'] for record in records: self._registry_route_records.append(to_route_record(record)) def set_route(self, route_id, index): self._master_scenario = None route_record = RouteRecord() route_record.route_id = route_id route_record.index = index if index < len(self._registry_route_records): # the element already exists and therefore we update it self._registry_route_records[index] = route_record else: self._registry_route_records.append(route_record) def set_scenario(self, scenario): """ Sets the scenario from which the statistics willb e taken """ self._master_scenario = scenario def compute_route_statistics(self, config, duration_time_system=-1, duration_time_game=-1, failure=""): """ Compute the current statistics by evaluating all relevant scenario criteria """ index = config.index if not self._registry_route_records or index >= len(self._registry_route_records): raise Exception('Critical error with the route registry.') # fetch latest record to fill in route_record = self._registry_route_records[index] target_reached = False score_penalty = 1.0 score_route = 0.0 route_record.meta['duration_system'] = duration_time_system route_record.meta['duration_game'] = duration_time_game route_record.meta['route_length'] = compute_route_length(config) route_record.meta['folder_name'] = config.folder_name route_record.meta['total_steps'] = config.agent.step if self._master_scenario: if self._master_scenario.timeout_node.timeout: route_record.infractions['route_timeout'].append('Route timeout.') failure = "Agent timed out" for node in self._master_scenario.get_criteria(): if node.list_traffic_events: # analyze all traffic events for event in node.list_traffic_events: if event.get_type() == TrafficEventType.COLLISION_STATIC: score_penalty *= PENALTY_COLLISION_STATIC route_record.infractions['collisions_layout'].append(event.get_message()) elif event.get_type() == TrafficEventType.COLLISION_PEDESTRIAN: score_penalty *= PENALTY_COLLISION_PEDESTRIAN route_record.infractions['collisions_pedestrian'].append(event.get_message()) elif event.get_type() == TrafficEventType.COLLISION_VEHICLE: score_penalty *= PENALTY_COLLISION_VEHICLE route_record.infractions['collisions_vehicle'].append(event.get_message()) elif event.get_type() == TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION: score_penalty *= (1 - event.get_dict()['percentage'] / 100) route_record.infractions['outside_route_lanes'].append(event.get_message()) elif event.get_type() == TrafficEventType.TRAFFIC_LIGHT_INFRACTION: score_penalty *= PENALTY_TRAFFIC_LIGHT route_record.infractions['red_light'].append(event.get_message()) elif event.get_type() == TrafficEventType.ROUTE_DEVIATION: route_record.infractions['route_dev'].append(event.get_message()) failure = "Agent deviated from the route" elif event.get_type() == TrafficEventType.STOP_INFRACTION: score_penalty *= PENALTY_STOP route_record.infractions['stop_infraction'].append(event.get_message()) elif event.get_type() == TrafficEventType.VEHICLE_BLOCKED: route_record.infractions['vehicle_blocked'].append(event.get_message()) failure = "Agent got blocked" elif event.get_type() == TrafficEventType.ROUTE_COMPLETED: score_route = 100.0 target_reached = True elif event.get_type() == TrafficEventType.ROUTE_COMPLETION: if not target_reached: if event.get_dict(): score_route = event.get_dict()['route_completed'] else: score_route = 0 # update route scores route_record.scores['score_route'] = score_route route_record.scores['score_penalty'] = score_penalty route_record.scores['score_composed'] = max(score_route*score_penalty, 0.0) # update status if target_reached: route_record.status = 'Completed' else: route_record.status = 'Failed' if failure: route_record.status += ' - ' + failure return route_record def compute_global_statistics(self, total_routes): global_record = RouteRecord() global_record.route_id = -1 global_record.index = -1 global_record.status = 'Completed' if self._registry_route_records: for route_record in self._registry_route_records: global_record.scores['score_route'] += route_record.scores['score_route'] global_record.scores['score_penalty'] += route_record.scores['score_penalty'] global_record.scores['score_composed'] += route_record.scores['score_composed'] for key in global_record.infractions.keys(): route_length_kms = max(route_record.scores['score_route'] * route_record.meta['route_length'] / 1000.0, 0.001) if isinstance(global_record.infractions[key], list): global_record.infractions[key] = len(route_record.infractions[key]) / route_length_kms else: global_record.infractions[key] += len(route_record.infractions[key]) / route_length_kms if route_record.status is not 'Completed': global_record.status = 'Failed' if 'exceptions' not in global_record.meta: global_record.meta['exceptions'] = [] global_record.meta['exceptions'].append((route_record.route_id, route_record.index, route_record.status)) global_record.scores['score_route'] /= float(total_routes) global_record.scores['score_penalty'] /= float(total_routes) global_record.scores['score_composed'] /= float(total_routes) return global_record @staticmethod def save_record(route_record, index, endpoint): data = fetch_dict(endpoint) if not data: data = create_default_json_msg() stats_dict = route_record.__dict__ record_list = data['_checkpoint']['records'] if index > len(record_list): print('Error! No enough entries in the list') sys.exit(-1) elif index == len(record_list): record_list.append(stats_dict) else: record_list[index] = stats_dict save_dict(endpoint, data) @staticmethod def save_global_record(route_record, sensors, total_routes, endpoint): data = fetch_dict(endpoint) if not data: data = create_default_json_msg() stats_dict = route_record.__dict__ data['_checkpoint']['global_record'] = stats_dict data['values'] = ['{:.3f}'.format(stats_dict['scores']['score_composed']), '{:.3f}'.format(stats_dict['scores']['score_route']), '{:.3f}'.format(stats_dict['scores']['score_penalty']), # infractions '{:.3f}'.format(stats_dict['infractions']['collisions_pedestrian']), '{:.3f}'.format(stats_dict['infractions']['collisions_vehicle']), '{:.3f}'.format(stats_dict['infractions']['collisions_layout']), '{:.3f}'.format(stats_dict['infractions']['red_light']), '{:.3f}'.format(stats_dict['infractions']['stop_infraction']), '{:.3f}'.format(stats_dict['infractions']['outside_route_lanes']), '{:.3f}'.format(stats_dict['infractions']['route_dev']), '{:.3f}'.format(stats_dict['infractions']['route_timeout']), '{:.3f}'.format(stats_dict['infractions']['vehicle_blocked']) ] data['labels'] = ['Avg. driving score', 'Avg. route completion', 'Avg. infraction penalty', 'Collisions with pedestrians', 'Collisions with vehicles', 'Collisions with layout', 'Red lights infractions', 'Stop sign infractions', 'Off-road infractions', 'Route deviations', 'Route timeouts', 'Agent blocked' ] entry_status = "Finished" eligible = True route_records = data["_checkpoint"]["records"] progress = data["_checkpoint"]["progress"] if progress[1] != total_routes: raise Exception('Critical error with the route registry.') if len(route_records) != total_routes or progress[0] != progress[1]: entry_status = "Finished with missing data" eligible = False else: for route in route_records: route_status = route["status"] if "Agent" in route_status: entry_status = "Finished with agent errors" break data['entry_status'] = entry_status data['eligible'] = eligible save_dict(endpoint, data) @staticmethod def save_sensors(sensors, endpoint): data = fetch_dict(endpoint) if not data: data = create_default_json_msg() if not data['sensors']: data['sensors'] = sensors save_dict(endpoint, data) @staticmethod def save_entry_status(entry_status, eligible, endpoint): data = fetch_dict(endpoint) if not data: data = create_default_json_msg() data['entry_status'] = entry_status data['eligible'] = eligible save_dict(endpoint, data) @staticmethod def clear_record(endpoint): if not endpoint.startswith(('http:', 'https:', 'ftp:')): with open(endpoint, 'w') as fd: fd.truncate(0) ================================================ FILE: leaderboard/scripts/collect_data.sh ================================================ #!/bin/bash export CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-0.9.10-py3.7-linux-x86_64.egg export PYTHONPATH=$PYTHONPATH:leaderboard export PYTHONPATH=$PYTHONPATH:leaderboard/team_code export PYTHONPATH=$PYTHONPATH:scenario_runner export PYTHONPATH=/mnt/petrelfs/share/pymc/new:$PYTHONPATH export LEADERBOARD_ROOT=leaderboard export CHALLENGE_TRACK_CODENAME=SENSORS export PORT=$1 export TM_PORT=$2 export DEBUG_CHALLENGE=0 export REPETITIONS=1 export RESUME=$4 export BENCHMARK=COLLECT_DATA # Roach data collection export ROUTES=leaderboard/data/routes_for_open_loop_training/routes_$3.xml export TEAM_AGENT=team_code/$6.py export TEAM_CONFIG=roach/config/config_agent.yaml export CHECKPOINT_ENDPOINT=data_collect_$3_results.json export SCENARIOS=leaderboard/data/scenarios/$7.json export SAVE_PATH=dataset/$3 export ROUTE_FILE=$3 python3 ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \ --scenarios=${SCENARIOS} \ --routes=${ROUTES} \ --repetitions=${REPETITIONS} \ --track=${CHALLENGE_TRACK_CODENAME} \ --checkpoint=collect_data_json/${CHECKPOINT_ENDPOINT} \ --agent=${TEAM_AGENT} \ --agent-config=${TEAM_CONFIG} \ --debug=${DEBUG_CHALLENGE} \ --record=${RECORD_PATH} \ --resume=${RESUME} \ --port=${PORT} \ --trafficManagerPort=${TM_PORT} \ --is_local=$5 \ --is_eval=False ================================================ FILE: leaderboard/scripts/evaluation_longest6.sh ================================================ #!/bin/bash export CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-0.9.10-py3.7-linux-x86_64.egg export PYTHONPATH=$PYTHONPATH:leaderboard export PYTHONPATH=$PYTHONPATH:leaderboard/team_code export PYTHONPATH=$PYTHONPATH:scenario_runner export PYTHONPATH=$PYTHONPATH:open_loop_training export PYTHONPATH=/mnt/lustre/share/pymc/new:$PYTHONPATH export LEADERBOARD_ROOT=leaderboard export CHALLENGE_TRACK_CODENAME=SENSORS export PORT=$1 export TM_PORT=$2 export DEBUG_CHALLENGE=0 export REPETITIONS=1 # multiple evaluation runs export RESUME=$4 #evaluation export ROUTES=leaderboard/data/routes_for_evaluation/routes_longest6.xml export TEAM_AGENT=team_code/$3.py export TEAM_CONFIG=$6 export CHECKPOINT_ENDPOINT=closed_loop_eval_log/results_$8.json export SCENARIOS=leaderboard/data/scenarios/$7.json export SAVE_PATH=closed_loop_eval_log/eval_log/$8 export BENCHMARK=longest6 python3 -q -X faulthandler ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \ --scenarios=${SCENARIOS} \ --routes=${ROUTES} \ --repetitions=${REPETITIONS} \ --track=${CHALLENGE_TRACK_CODENAME} \ --checkpoint=${CHECKPOINT_ENDPOINT} \ --agent=${TEAM_AGENT} \ --agent-config=${TEAM_CONFIG} \ --debug=${DEBUG_CHALLENGE} \ --record=${RECORD_PATH} \ --resume=${RESUME} \ --port=${PORT} \ --trafficManagerPort=${TM_PORT} \ --is_local=$5 \ --is_eval=True ================================================ FILE: leaderboard/scripts/evaluation_town05long.sh ================================================ #!/bin/bash export CARLA_SERVER=${CARLA_ROOT}/CarlaUE4.sh export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-0.9.10-py3.7-linux-x86_64.egg export PYTHONPATH=$PYTHONPATH:leaderboard export PYTHONPATH=$PYTHONPATH:leaderboard/team_code export PYTHONPATH=$PYTHONPATH:scenario_runner export PYTHONPATH=$PYTHONPATH:open_loop_training export PYTHONPATH=/mnt/lustre/share/pymc/new:$PYTHONPATH export LEADERBOARD_ROOT=leaderboard export CHALLENGE_TRACK_CODENAME=SENSORS export PORT=$1 export TM_PORT=$2 export DEBUG_CHALLENGE=0 export REPETITIONS=1 # multiple evaluation runs export RESUME=$4 # evaluation export ROUTES=leaderboard/data/routes_for_evaluation/routes_town05_long.xml export TEAM_AGENT=team_code/$3.py export TEAM_CONFIG=$6 export CHECKPOINT_ENDPOINT=closed_loop_eval_log/results_$8.json export SCENARIOS=leaderboard/data/scenarios/$7.json export SAVE_PATH=closed_loop_eval_log/eval_log/$8 export BENCHMARK=town05long python3 -q -X faulthandler ${LEADERBOARD_ROOT}/leaderboard/leaderboard_evaluator.py \ --scenarios=${SCENARIOS} \ --routes=${ROUTES} \ --repetitions=${REPETITIONS} \ --track=${CHALLENGE_TRACK_CODENAME} \ --checkpoint=${CHECKPOINT_ENDPOINT} \ --agent=${TEAM_AGENT} \ --agent-config=${TEAM_CONFIG} \ --debug=${DEBUG_CHALLENGE} \ --record=${RECORD_PATH} \ --resume=${RESUME} \ --port=${PORT} \ --trafficManagerPort=${TM_PORT} \ --is_local=$5 \ --is_eval=True ================================================ FILE: leaderboard/team_code/auto_pilot.py ================================================ import os import time import datetime import pathlib import json import random import numpy as np import cv2 import carla from PIL import Image from team_code.map_agent import MapAgent from team_code.pid_controller import PIDController # WEATHERS = { # 'ClearNoon': carla.WeatherParameters.ClearNoon, # 'ClearSunset': carla.WeatherParameters.ClearSunset, # 'CloudyNoon': carla.WeatherParameters.CloudyNoon, # 'CloudySunset': carla.WeatherParameters.CloudySunset, # 'WetNoon': carla.WeatherParameters.WetNoon, # 'WetSunset': carla.WeatherParameters.WetSunset, # 'MidRainyNoon': carla.WeatherParameters.MidRainyNoon, # 'MidRainSunset': carla.WeatherParameters.MidRainSunset, # 'WetCloudyNoon': carla.WeatherParameters.WetCloudyNoon, # 'WetCloudySunset': carla.WeatherParameters.WetCloudySunset, # 'HardRainNoon': carla.WeatherParameters.HardRainNoon, # 'HardRainSunset': carla.WeatherParameters.HardRainSunset, # 'SoftRainNoon': carla.WeatherParameters.SoftRainNoon, # 'SoftRainSunset': carla.WeatherParameters.SoftRainSunset, # } # WEATHERS_IDS = list(WEATHERS) WEATHERS = { 'ClearNoon': carla.WeatherParameters.ClearNoon, 'ClearSunset': carla.WeatherParameters.ClearSunset, 'WetNoon': carla.WeatherParameters.WetNoon, # 'WetSunset': carla.WeatherParameters.WetSunset, 'HardRainNoon': carla.WeatherParameters.HardRainNoon, # 'SoftRainSunset': carla.WeatherParameters.SoftRainSunset, } WEATHERS_IDS = list(WEATHERS) def get_entry_point(): return 'AutoPilot' def _numpy(carla_vector, normalize=False): result = np.float32([carla_vector.x, carla_vector.y]) if normalize: return result / (np.linalg.norm(result) + 1e-4) return result def _location(x, y, z): return carla.Location(x=float(x), y=float(y), z=float(z)) def _orientation(yaw): return np.float32([np.cos(np.radians(yaw)), np.sin(np.radians(yaw))]) def get_collision(p1, v1, p2, v2): A = np.stack([v1, -v2], 1) b = p2 - p1 if abs(np.linalg.det(A)) < 1e-3: return False, None x = np.linalg.solve(A, b) collides = all(x >= 0) and all(x <= 1) # how many seconds until collision return collides, p1 + x[0] * v1 def check_episode_has_noise(lat_noise_percent, long_noise_percent): lat_noise = False long_noise = False if random.randint(0, 101) < lat_noise_percent: lat_noise = True if random.randint(0, 101) < long_noise_percent: long_noise = True return lat_noise, long_noise class AutoPilot(MapAgent): # for stop signs PROXIMITY_THRESHOLD = 30.0 # meters SPEED_THRESHOLD = 0.1 WAYPOINT_STEP = 1.0 # meters def setup(self, path_to_conf_file): super().setup(path_to_conf_file) def _init(self): super()._init() self._turn_controller = PIDController(K_P=1.25, K_I=0.75, K_D=0.3, n=40) self._speed_controller = PIDController(K_P=5.0, K_I=0.5, K_D=1.0, n=40) # for stop signs self._target_stop_sign = None # the stop sign affecting the ego vehicle self._stop_completed = False # if the ego vehicle has completed the stop sign self._affected_by_stop = False # if the ego vehicle is influenced by a stop sign def _get_angle_to(self, pos, theta, target): R = np.array([ [np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)], ]) aim = R.T.dot(target - pos) angle = -np.degrees(np.arctan2(-aim[1], aim[0])) angle = 0.0 if np.isnan(angle) else angle return angle def _get_control(self, target, far_target, tick_data): pos = self._get_position(tick_data) theta = tick_data['compass'] speed = tick_data['speed'] # Steering. angle_unnorm = self._get_angle_to(pos, theta, target) angle = angle_unnorm / 90 steer = self._turn_controller.step(angle) steer = np.clip(steer, -1.0, 1.0) steer = round(steer, 3) # Acceleration. angle_far_unnorm = self._get_angle_to(pos, theta, far_target) should_slow = abs(angle_far_unnorm) > 45.0 or abs(angle_unnorm) > 5.0 target_speed = 4.0 if should_slow else 7.0 brake = self._should_brake() target_speed = target_speed if not brake else 0.0 self.should_slow = int(should_slow) self.should_brake = int(brake) self.angle = angle self.angle_unnorm = angle_unnorm self.angle_far_unnorm = angle_far_unnorm delta = np.clip(target_speed - speed, 0.0, 0.25) throttle = self._speed_controller.step(delta) throttle = np.clip(throttle, 0.0, 0.75) if brake: steer *= 0.5 throttle = 0.0 return steer, throttle, brake, target_speed def run_step(self, input_data, timestamp): if not self.initialized: self._init() # change weather for visual diversity if self.step % 10 == 0: index = random.choice(range(len(WEATHERS))) self.weather_id = WEATHERS_IDS[index] weather = WEATHERS[WEATHERS_IDS[index]] print (self.weather_id, weather) self._world.set_weather(weather) data = self.tick(input_data) gps = self._get_position(data) near_node, near_command = self._waypoint_planner.run_step(gps) far_node, far_command = self._command_planner.run_step(gps) steer, throttle, brake, target_speed = self._get_control(near_node, far_node, data) control = carla.VehicleControl() control.steer = steer + 1e-2 * np.random.randn() control.throttle = throttle control.brake = float(brake) if self.step % 10 == 0 and self.save_path is not None: self.save(near_node, far_node, near_command, steer, throttle, brake, target_speed, data) return control def _should_brake(self): actors = self._world.get_actors() vehicle = self._is_vehicle_hazard(actors.filter('*vehicle*')) light = self._is_light_red(actors.filter('*traffic_light*')) walker = self._is_walker_hazard(actors.filter('*walker*')) stop_sign = self._is_stop_sign_hazard(actors.filter('*stop*')) self.is_vehicle_present = 1 if vehicle is not None else 0 self.is_red_light_present = 1 if light is not None else 0 self.is_pedestrian_present = 1 if walker is not None else 0 self.is_stop_sign_present = 1 if stop_sign is not None else 0 return any(x is not None for x in [vehicle, light, walker, stop_sign]) def _point_inside_boundingbox(self, point, bb_center, bb_extent): A = carla.Vector2D(bb_center.x - bb_extent.x, bb_center.y - bb_extent.y) B = carla.Vector2D(bb_center.x + bb_extent.x, bb_center.y - bb_extent.y) D = carla.Vector2D(bb_center.x - bb_extent.x, bb_center.y + bb_extent.y) M = carla.Vector2D(point.x, point.y) AB = B - A AD = D - A AM = M - A am_ab = AM.x * AB.x + AM.y * AB.y ab_ab = AB.x * AB.x + AB.y * AB.y am_ad = AM.x * AD.x + AM.y * AD.y ad_ad = AD.x * AD.x + AD.y * AD.y return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad def _get_forward_speed(self, transform=None, velocity=None): """ Convert the vehicle transform directly to forward speed """ if not velocity: velocity = self._vehicle.get_velocity() if not transform: transform = self._vehicle.get_transform() vel_np = np.array([velocity.x, velocity.y, velocity.z]) pitch = np.deg2rad(transform.rotation.pitch) yaw = np.deg2rad(transform.rotation.yaw) orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)]) speed = np.dot(vel_np, orientation) return speed def _is_actor_affected_by_stop(self, actor, stop, multi_step=20): """ Check if the given actor is affected by the stop """ affected = False # first we run a fast coarse test current_location = actor.get_location() stop_location = stop.get_transform().location if stop_location.distance(current_location) > self.PROXIMITY_THRESHOLD: return affected stop_t = stop.get_transform() transformed_tv = stop_t.transform(stop.trigger_volume.location) # slower and accurate test based on waypoint's horizon and geometric test list_locations = [current_location] waypoint = self._world.get_map().get_waypoint(current_location) for _ in range(multi_step): if waypoint: waypoint = waypoint.next(self.WAYPOINT_STEP)[0] if not waypoint: break list_locations.append(waypoint.transform.location) for actor_location in list_locations: if self._point_inside_boundingbox(actor_location, transformed_tv, stop.trigger_volume.extent): affected = True return affected def _is_stop_sign_hazard(self, stop_sign_list): if self._affected_by_stop: if not self._stop_completed: current_speed = self._get_forward_speed() if current_speed < self.SPEED_THRESHOLD: self._stop_completed = True return None else: return self._target_stop_sign else: # reset if the ego vehicle is outside the influence of the current stop sign if not self._is_actor_affected_by_stop(self._vehicle, self._target_stop_sign): self._affected_by_stop = False self._stop_completed = False self._target_stop_sign = None return None ve_tra = self._vehicle.get_transform() ve_dir = ve_tra.get_forward_vector() wp = self._world.get_map().get_waypoint(ve_tra.location) wp_dir = wp.transform.get_forward_vector() dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z if dot_ve_wp > 0: # Ignore all when going in a wrong lane for stop_sign in stop_sign_list: if self._is_actor_affected_by_stop(self._vehicle, stop_sign): # this stop sign is affecting the vehicle self._affected_by_stop = True self._target_stop_sign = stop_sign return self._target_stop_sign return None def _is_light_red(self, lights_list): if self._vehicle.get_traffic_light_state() != carla.libcarla.TrafficLightState.Green: affecting = self._vehicle.get_traffic_light() for light in self._traffic_lights: if light.id == affecting.id: return affecting return None def _is_walker_hazard(self, walkers_list): z = self._vehicle.get_location().z p1 = _numpy(self._vehicle.get_location()) v1 = 10.0 * _orientation(self._vehicle.get_transform().rotation.yaw) for walker in walkers_list: v2_hat = _orientation(walker.get_transform().rotation.yaw) s2 = np.linalg.norm(_numpy(walker.get_velocity())) if s2 < 0.05: v2_hat *= s2 p2 = -3.0 * v2_hat + _numpy(walker.get_location()) v2 = 8.0 * v2_hat collides, collision_point = get_collision(p1, v1, p2, v2) if collides: return walker return None def _is_vehicle_hazard(self, vehicle_list): z = self._vehicle.get_location().z o1 = _orientation(self._vehicle.get_transform().rotation.yaw) p1 = _numpy(self._vehicle.get_location()) s1 = max(10, 3.0 * np.linalg.norm(_numpy(self._vehicle.get_velocity()))) # increases the threshold distance v1_hat = o1 v1 = s1 * v1_hat for target_vehicle in vehicle_list: if target_vehicle.id == self._vehicle.id: continue o2 = _orientation(target_vehicle.get_transform().rotation.yaw) p2 = _numpy(target_vehicle.get_location()) s2 = max(5.0, 2.0 * np.linalg.norm(_numpy(target_vehicle.get_velocity()))) v2_hat = o2 v2 = s2 * v2_hat p2_p1 = p2 - p1 distance = np.linalg.norm(p2_p1) p2_p1_hat = p2_p1 / (distance + 1e-4) angle_to_car = np.degrees(np.arccos(v1_hat.dot(p2_p1_hat))) angle_between_heading = np.degrees(np.arccos(o1.dot(o2))) # to consider -ve angles too angle_to_car = min(angle_to_car, 360.0 - angle_to_car) angle_between_heading = min(angle_between_heading, 360.0 - angle_between_heading) if angle_between_heading > 60.0 and not (angle_to_car < 15 and distance < s1): continue elif angle_to_car > 30.0: continue elif distance > s1: continue return target_vehicle return None ================================================ FILE: leaderboard/team_code/base_agent.py ================================================ import time import os import datetime import pathlib import json import cv2 import carla from leaderboard.autoagents import autonomous_agent from team_code.planner import RoutePlanner import numpy as np from PIL import Image, ImageDraw SAVE_PATH = os.environ.get('SAVE_PATH', None) class BaseAgent(autonomous_agent.AutonomousAgent): def setup(self, path_to_conf_file): self.track = autonomous_agent.Track.SENSORS self.config_path = path_to_conf_file self.step = -1 self.wall_start = time.time() self.initialized = False self._sensor_data = { 'width': 400, 'height': 300, 'fov': 100 } self._3d_bb_distance = 50 self.weather_id = None self.save_path = None if SAVE_PATH is not None: now = datetime.datetime.now() string = pathlib.Path(os.environ['ROUTES']).stem + '_' string += '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second))) print (string) self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string self.save_path.mkdir(parents=True, exist_ok=False) for sensor in self.sensors(): if hasattr(sensor, 'save') and sensor['save']: (self.save_path / sensor['id']).mkdir() (self.save_path / '3d_bbs').mkdir(parents=True, exist_ok=True) (self.save_path / 'affordances').mkdir(parents=True, exist_ok=True) (self.save_path / 'measurements').mkdir(parents=True, exist_ok=True) (self.save_path / 'lidar').mkdir(parents=True, exist_ok=True) (self.save_path / 'semantic_lidar').mkdir(parents=True, exist_ok=True) (self.save_path / 'topdown').mkdir(parents=True, exist_ok=True) for pos in ['front', 'left', 'right', 'rear']: for sensor_type in ['rgb', 'seg', 'depth', '2d_bbs']: name = sensor_type + '_' + pos (self.save_path / name).mkdir() def _init(self): self._command_planner = RoutePlanner(7.5, 25.0, 257) self._command_planner.set_route(self._global_plan, True) self.initialized = True self._sensor_data['calibration'] = self._get_camera_to_car_calibration(self._sensor_data) self._sensors = self.sensor_interface._sensors_objects def _get_position(self, tick_data): gps = tick_data['gps'] gps = (gps - self._command_planner.mean) * self._command_planner.scale return gps def sensors(self): return [ { 'type': 'sensor.camera.rgb', 'x': -1.5, 'y': 0.0, 'z': 2.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 900, 'height': 256, 'fov': 100, 'id': 'rgb_front' }, { 'type': 'sensor.camera.semantic_segmentation', 'x': 1.3, 'y': 0.0, 'z': 2.3, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], 'id': 'seg_front' }, { 'type': 'sensor.camera.depth', 'x': 1.3, 'y': 0.0, 'z': 2.3, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], 'id': 'depth_front' }, # { # 'type': 'sensor.camera.rgb', # 'x': -1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'rgb_rear' # }, # { # 'type': 'sensor.camera.semantic_segmentation', # 'x': -1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'seg_rear' # }, # { # 'type': 'sensor.camera.depth', # 'x': -1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'depth_rear' # }, # { # 'type': 'sensor.camera.rgb', # 'x': 1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': -60.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'rgb_left' # }, # { # 'type': 'sensor.camera.semantic_segmentation', # 'x': 1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': -60.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'seg_left' # }, # { # 'type': 'sensor.camera.depth', # 'x': 1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': -60.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'depth_left' # }, # { # 'type': 'sensor.camera.rgb', # 'x': 1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': 60.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'rgb_right' # }, # { # 'type': 'sensor.camera.semantic_segmentation', # 'x': 1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': 60.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'seg_right' # }, # { # 'type': 'sensor.camera.depth', # 'x': 1.3, 'y': 0.0, 'z': 2.3, # 'roll': 0.0, 'pitch': 0.0, 'yaw': 60.0, # 'width': self._sensor_data['width'], 'height': self._sensor_data['height'], 'fov': self._sensor_data['fov'], # 'id': 'depth_right' # }, # { # 'type': 'sensor.lidar.ray_cast', # 'x': 1.3, 'y': 0.0, 'z': 2.5, # 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, # 'id': 'lidar' # }, # { # 'type': 'sensor.lidar.ray_cast_semantic', # 'x': 1.3, 'y': 0.0, 'z': 2.5, # 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, # 'id': 'semantic_lidar' # }, { 'type': 'sensor.other.imu', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.05, 'id': 'imu' }, { 'type': 'sensor.other.gnss', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.01, 'id': 'gps' }, { 'type': 'sensor.speedometer', 'reading_frequency': 20, 'id': 'speed' } ] def tick(self, input_data): self.step += 1 # affordances = self._get_affordances() # traffic_lights = self._find_obstacle('*traffic_light*') # stop_signs = self._find_obstacle('*stop*') depth = {} seg = {} # bb_3d = self._get_3d_bbs(max_distance=self._3d_bb_distance) bb_2d = {} # for pos in ['front', 'left', 'right', 'rear']: # seg_cam = 'seg_' + pos # depth_cam = 'depth_' + pos # _segmentation = np.copy(input_data[seg_cam][1][:, :, 2]) # depth[pos] = self._get_depth(input_data[depth_cam][1][:, :, :3]) # self._change_seg_tl(_segmentation, depth[pos], traffic_lights) # self._change_seg_stop(_segmentation, depth[pos], stop_signs, seg_cam) # bb_2d[pos] = self._get_2d_bbs(seg_cam, affordances, bb_3d, _segmentation) # #self._draw_2d_bbs(_segmentation, bb_2d[pos]) # seg[pos] = _segmentation rgb_front = cv2.cvtColor(input_data['rgb_front'][1][:, :, :3], cv2.COLOR_BGR2RGB) # rgb_rear = cv2.cvtColor(input_data['rgb_rear'][1][:, :, :3], cv2.COLOR_BGR2RGB) # rgb_left = cv2.cvtColor(input_data['rgb_left'][1][:, :, :3], cv2.COLOR_BGR2RGB) # rgb_right = cv2.cvtColor(input_data['rgb_right'][1][:, :, :3], cv2.COLOR_BGR2RGB) gps = input_data['gps'][1][:2] speed = input_data['speed'][1]['speed'] compass = input_data['imu'][1][-1] # depth_front = cv2.cvtColor(input_data['depth_front'][1][:, :, :3], cv2.COLOR_BGR2RGB) # depth_left = cv2.cvtColor(input_data['depth_left'][1][:, :, :3], cv2.COLOR_BGR2RGB) # depth_right = cv2.cvtColor(input_data['depth_right'][1][:, :, :3], cv2.COLOR_BGR2RGB) # depth_rear = cv2.cvtColor(input_data['depth_rear'][1][:, :, :3], cv2.COLOR_BGR2RGB) weather = self._weather_to_dict(self._world.get_weather()) # return { # 'rgb_front': rgb_front, # 'seg_front': seg['front'], # 'depth_front': depth_front, # '2d_bbs_front': bb_2d['front'], # 'rgb_rear': rgb_rear, # 'seg_rear': seg['rear'], # 'depth_rear': depth_rear, # '2d_bbs_rear': bb_2d['rear'], # 'rgb_left': rgb_left, # 'seg_left': seg['left'], # 'depth_left': depth_left, # '2d_bbs_left': bb_2d['left'], # 'rgb_right': rgb_right, # 'seg_right': seg['right'], # 'depth_right': depth_right, # '2d_bbs_right': bb_2d['right'], # 'lidar' : input_data['lidar'][1], # 'semantic_lidar': input_data['semantic_lidar'][1], # 'gps': gps, # 'speed': speed, # 'compass': compass, # 'weather': weather, # 'affordances': affordances, # '3d_bbs': bb_3d # } return { 'rgb_front': rgb_front, 'gps': gps, 'speed': speed, 'compass': compass, 'weather': weather, } def save(self, near_node, far_node, near_command, steer, throttle, brake, target_speed, tick_data): frame = self.step // 10 pos = self._get_position(tick_data) theta = tick_data['compass'] speed = tick_data['speed'] weather = tick_data['weather'] data = { 'x': pos[0], 'y': pos[1], 'theta': theta, 'speed': speed, 'target_speed': target_speed, 'x_command': far_node[0], 'y_command': far_node[1], 'command': near_command.value, 'steer': steer, 'throttle': throttle, 'brake': brake, 'weather': weather, 'weather_id': self.weather_id, 'near_node_x': near_node[0], 'near_node_y': near_node[1], 'far_node_x': far_node[0], 'far_node_y': far_node[1], 'is_vehicle_present': self.is_vehicle_present, 'is_pedestrian_present': self.is_pedestrian_present, 'is_red_light_present': self.is_red_light_present, 'is_stop_sign_present': self.is_stop_sign_present, 'should_slow': self.should_slow, 'should_brake': self.should_brake, 'angle': self.angle, 'angle_unnorm': self.angle_unnorm, 'angle_far_unnorm': self.angle_far_unnorm, } measurements_file = self.save_path / 'measurements' / ('%04d.json' % frame) f = open(measurements_file, 'w') json.dump(data, f, indent=4) f.close() # for pos in ['front', 'left', 'right', 'rear']: for pos in ['front']: name = 'rgb_' + pos Image.fromarray(tick_data[name]).save(self.save_path / name / ('%04d.png' % frame)) # for sensor_type in ['seg', 'depth']: # name = sensor_type + '_' + pos # Image.fromarray(tick_data[name]).save(self.save_path / name / ('%04d.png' % frame)) # for sensor_type in ['2d_bbs']: # name = sensor_type + '_' + pos # np.save(self.save_path / name / ('%04d.npy' % frame), tick_data[name], allow_pickle=True) # Image.fromarray(tick_data['topdown']).save(self.save_path / 'topdown' / ('%04d.png' % frame)) # np.save(self.save_path / 'lidar' / ('%04d.npy' % frame), tick_data['lidar'], allow_pickle=True) # np.save(self.save_path / 'semantic_lidar' / ('%04d.npy' % frame), tick_data['semantic_lidar'], allow_pickle=True) # np.save(self.save_path / '3d_bbs' / ('%04d.npy' % frame), tick_data['3d_bbs'], allow_pickle=True) # np.save(self.save_path / 'affordances' / ('%04d.npy' % frame), tick_data['affordances'], allow_pickle=True) def _weather_to_dict(self, carla_weather): weather = { 'cloudiness': carla_weather.cloudiness, 'precipitation': carla_weather.precipitation, 'precipitation_deposits': carla_weather.precipitation_deposits, 'wind_intensity': carla_weather.wind_intensity, 'sun_azimuth_angle': carla_weather.sun_azimuth_angle, 'sun_altitude_angle': carla_weather.sun_altitude_angle, 'fog_density': carla_weather.fog_density, 'fog_distance': carla_weather.fog_distance, 'wetness': carla_weather.wetness, 'fog_falloff': carla_weather.fog_falloff, } return weather def _create_bb_points(self, bb): """ Returns 3D bounding box world coordinates. """ cords = np.zeros((8, 4)) extent = bb[1] loc = bb[0] cords[0, :] = np.array([loc[0] + extent[0], loc[1] + extent[1], loc[2] - extent[2], 1]) cords[1, :] = np.array([loc[0] - extent[0], loc[1] + extent[1], loc[2] - extent[2], 1]) cords[2, :] = np.array([loc[0] - extent[0], loc[1] - extent[1], loc[2] - extent[2], 1]) cords[3, :] = np.array([loc[0] + extent[0], loc[1] - extent[1], loc[2] - extent[2], 1]) cords[4, :] = np.array([loc[0] + extent[0], loc[1] + extent[1], loc[2] + extent[2], 1]) cords[5, :] = np.array([loc[0] - extent[0], loc[1] + extent[1], loc[2] + extent[2], 1]) cords[6, :] = np.array([loc[0] - extent[0], loc[1] - extent[1], loc[2] + extent[2], 1]) cords[7, :] = np.array([loc[0] + extent[0], loc[1] - extent[1], loc[2] + extent[2], 1]) return cords def _translate_tl_state(self, state): if state == carla.TrafficLightState.Red: return 0 elif state == carla.TrafficLightState.Yellow: return 1 elif state == carla.TrafficLightState.Green: return 2 elif state == carla.TrafficLightState.Off: return 3 elif state == carla.TrafficLightState.Unknown: return 4 else: return None def _get_affordances(self): # affordance tl affordances = {} affordances["traffic_light"] = None affecting = self._vehicle.get_traffic_light() if affecting is not None: for light in self._traffic_lights: if light.id == affecting.id: affordances["traffic_light"] = self._translate_tl_state(self._vehicle.get_traffic_light_state()) affordances["stop_sign"] = self._affected_by_stop return affordances def _get_3d_bbs(self, max_distance=50): bounding_boxes = { "traffic_lights": [], "stop_signs": [], "vehicles": [], "pedestrians": [] } bounding_boxes['traffic_lights'] = self._find_obstacle_3dbb('*traffic_light*', max_distance) bounding_boxes['stop_signs'] = self._find_obstacle_3dbb('*stop*', max_distance) bounding_boxes['vehicles'] = self._find_obstacle_3dbb('*vehicle*', max_distance) bounding_boxes['pedestrians'] = self._find_obstacle_3dbb('*walker*', max_distance) return bounding_boxes def _get_2d_bbs(self, seg_cam, affordances, bb_3d, seg_img): """Returns a dict of all 2d boundingboxes given a camera position, affordances and 3d bbs Args: seg_cam ([type]): [description] affordances ([type]): [description] bb_3d ([type]): [description] Returns: [type]: [description] """ bounding_boxes = { "traffic_light": list(), "stop_sign": list(), "vehicles": list(), "pedestrians": list() } if affordances['stop_sign']: baseline = self._get_2d_bb_baseline(self._target_stop_sign) bb = self._baseline_to_box(baseline, seg_cam) if bb is not None: bounding_boxes["stop_sign"].append(bb) if affordances['traffic_light'] is not None: baseline = self._get_2d_bb_baseline(self._vehicle.get_traffic_light(), distance=8) tl_bb = self._baseline_to_box(baseline, seg_cam, height=.5) if tl_bb is not None: bounding_boxes["traffic_light"].append({ "bb": tl_bb, "state": self._translate_tl_state(self._vehicle.get_traffic_light_state()) }) for vehicle in bb_3d["vehicles"]: trig_loc_world = self._create_bb_points(vehicle).T cords_x_y_z = self._world_to_sensor(trig_loc_world, self._get_sensor_position(seg_cam), False) cords_x_y_z = np.array(cords_x_y_z)[:3, :] veh_bb = self._coords_to_2d_bb(cords_x_y_z) if veh_bb is not None: if np.any(seg_img[veh_bb[0][1]:veh_bb[1][1],veh_bb[0][0]:veh_bb[1][0]] == 10): bounding_boxes["vehicles"].append(veh_bb) for pedestrian in bb_3d["pedestrians"]: trig_loc_world = self._create_bb_points(pedestrian).T cords_x_y_z = self._world_to_sensor(trig_loc_world, self._get_sensor_position(seg_cam), False) cords_x_y_z = np.array(cords_x_y_z)[:3, :] ped_bb = self._coords_to_2d_bb(cords_x_y_z) if ped_bb is not None: if np.any(seg_img[ped_bb[0][1]:ped_bb[1][1],ped_bb[0][0]:ped_bb[1][0]] == 4): bounding_boxes["pedestrians"].append(ped_bb) return bounding_boxes def _draw_2d_bbs(self, seg_img, bbs): """For debugging only Args: seg_img ([type]): [description] bbs ([type]): [description] """ for bb_type in bbs: _region = np.zeros(seg_img.shape) if bb_type == "traffic_light": for bb in bbs[bb_type]: _region = np.zeros(seg_img.shape) box = bb['bb'] _region[box[0][1]:box[1][1],box[0][0]:box[1][0]] = 1 seg_img[(_region == 1)] = 23 else: for bb in bbs[bb_type]: _region[bb[0][1]:bb[1][1],bb[0][0]:bb[1][0]] = 1 if bb_type == "stop_sign": seg_img[(_region == 1)] = 26 elif bb_type == "vehicles": seg_img[(_region == 1)] = 10 elif bb_type == "pedestrians": seg_img[(_region == 1)] = 4 def _find_obstacle_3dbb(self, obstacle_type, max_distance=50): """Returns a list of 3d bounding boxes of type obstacle_type. If the object does have a bounding box, this is returned. Otherwise a bb of size 0.5,0.5,2 is returned at the origin of the object. Args: obstacle_type (String): Regular expression max_distance (int, optional): max search distance. Returns all bbs in this radius. Defaults to 50. Returns: List: List of Boundingboxes """ obst = list() _actors = self._world.get_actors() _obstacles = _actors.filter(obstacle_type) for _obstacle in _obstacles: distance_to_car = _obstacle.get_transform().location.distance(self._vehicle.get_location()) if 0 < distance_to_car <= max_distance: if hasattr(_obstacle, 'bounding_box'): loc = _obstacle.bounding_box.location _obstacle.get_transform().transform(loc) extent = _obstacle.bounding_box.extent _rotation_matrix = self.get_matrix(carla.Transform(carla.Location(0,0,0), _obstacle.get_transform().rotation)) rotated_extent = np.squeeze(np.array((np.array([[extent.x, extent.y, extent.z, 1]]) @ _rotation_matrix)[:3])) bb = np.array([ [loc.x, loc.y, loc.z], [rotated_extent[0], rotated_extent[1], rotated_extent[2]] ]) else: loc = _obstacle.get_transform().location bb = np.array([ [loc.x, loc.y, loc.z], [0.5, 0.5, 2] ]) obst.append(bb) return obst def _get_2d_bb_baseline(self, obstacle, distance=2, cam='seg_front'): """Returns 2 coordinates for the baseline for 2d bbs in world coordinates (distance behind trigger volume, as seen from camera) Args: obstacle (Actor): obstacle with distance (int, optional): Distance behind trigger volume. Defaults to 2. Returns: np.ndarray: Baseline """ trigger = obstacle.trigger_volume bb = self._create_2d_bb_points(trigger) trig_loc_world = self._trig_to_world(bb, obstacle, trigger) #self._draw_line(trig_loc_world[:,0], trig_loc_world[:,3], 0.7, color=(0, 255, 255)) cords_x_y_z = np.array(self._world_to_sensor(trig_loc_world, self._get_sensor_position(cam))) indices = (-cords_x_y_z[0]).argsort() # check crooked up boxes if self._get_dist(cords_x_y_z[:,indices[0]],cords_x_y_z[:,indices[1]]) < self._get_dist(cords_x_y_z[:,indices[0]],cords_x_y_z[:,indices[2]]): cords = cords_x_y_z[:, [indices[0],indices[2]]] + np.array([[distance],[0],[0],[0]]) else: cords = cords_x_y_z[:, [indices[0],indices[1]]] + np.array([[distance],[0],[0],[0]]) sensor_world_matrix = self.get_matrix(self._get_sensor_position(cam)) baseline = np.dot(sensor_world_matrix, cords) return baseline def _baseline_to_box(self, baseline, cam, height=1): """Transforms a baseline (in world coords) into a 2d box (in sensor coords) Args: baseline ([type]): [description] cam ([type]): [description] height (int, optional): Box height. Defaults to 1. Returns: [type]: Box in sensor coords """ cords_x_y_z = np.array(self._world_to_sensor(baseline, self._get_sensor_position(cam))[:3, :]) cords = np.hstack((cords_x_y_z, np.fliplr(cords_x_y_z + np.array([[0],[0],[height]])))) return self._coords_to_2d_bb(cords) def _coords_to_2d_bb(self, cords): """Returns coords of a 2d box given points in sensor coords Args: cords ([type]): [description] Returns: [type]: [description] """ cords_y_minus_z_x = np.vstack((cords[1, :], -cords[2, :], cords[0, :])) bbox = (self._sensor_data['calibration'] @ cords_y_minus_z_x).T camera_bbox = np.vstack([bbox[:, 0] / bbox[:, 2], bbox[:, 1] / bbox[:, 2], bbox[:, 2]]).T if np.any(camera_bbox[:,2] > 0): camera_bbox = np.array(camera_bbox) _positive_bb = camera_bbox[camera_bbox[:,2] > 0] min_x = int(np.clip(np.min(_positive_bb[:,0]), 0, self._sensor_data['width'])) min_y = int(np.clip(np.min(_positive_bb[:,1]), 0, self._sensor_data['height'])) max_x = int(np.clip(np.max(_positive_bb[:,0]), 0, self._sensor_data['width'])) max_y = int(np.clip(np.max(_positive_bb[:,1]), 0, self._sensor_data['height'])) return [(min_x,min_y),(max_x,max_y)] else: return None def _change_seg_stop(self, seg_img, depth_img, stop_signs, cam, _region_size=6): """Adds a stop class to the segmentation image Args: seg_img ([type]): [description] depth_img ([type]): [description] stop_signs ([type]): [description] cam ([type]): [description] _region_size (int, optional): [description]. Defaults to 6. """ for stop in stop_signs: _dist = self._get_distance(stop.get_transform().location) _region = np.abs(depth_img - _dist) seg_img[(_region < _region_size) & (seg_img == 12)] = 26 # lane markings trigger = stop.trigger_volume _trig_loc_world = self._trig_to_world(np.array([[0], [0], [0], [1.0]]).T, stop, trigger) _x = self._world_to_sensor(_trig_loc_world, self._get_sensor_position(cam))[0,0] if _x > 0: # stop is in front of camera bb = self._create_2d_bb_points(trigger, 4) trig_loc_world = self._trig_to_world(bb, stop, trigger) cords_x_y_z = self._world_to_sensor(trig_loc_world, self._get_sensor_position(cam), True) #if cords_x_y_z.size: cords_x_y_z = cords_x_y_z[:3, :] cords_y_minus_z_x = np.concatenate([cords_x_y_z[1, :], -cords_x_y_z[2, :], cords_x_y_z[0, :]]) bbox = (self._sensor_data['calibration'] @ cords_y_minus_z_x).T camera_bbox = np.concatenate([bbox[:, 0] / bbox[:, 2], bbox[:, 1] / bbox[:, 2], bbox[:, 2]], axis=1) if np.any(camera_bbox[:,2] > 0): camera_bbox = np.array(camera_bbox) polygon = [(camera_bbox[i, 0], camera_bbox[i, 1]) for i in range(len(camera_bbox))] img = Image.new('L', (self._sensor_data['width'], self._sensor_data['height']), 0) ImageDraw.Draw(img).polygon(polygon, outline=1, fill=1) _region = np.array(img) #seg_img[(_region == 1)] = 27 seg_img[(_region == 1) & (seg_img == 6)] = 27 def _trig_to_world(self, bb, parent, trigger): """Transforms the trigger coordinates to world coordinates Args: bb ([type]): [description] parent ([type]): [description] trigger ([type]): [description] Returns: [type]: [description] """ bb_transform = carla.Transform(trigger.location) bb_vehicle_matrix = self.get_matrix(bb_transform) vehicle_world_matrix = self.get_matrix(parent.get_transform()) bb_world_matrix = vehicle_world_matrix @ bb_vehicle_matrix world_cords = bb_world_matrix @ bb.T return world_cords def _create_2d_bb_points(self, actor_bb, scale_factor=1): """ Returns 2D floor bounding box for an actor. """ cords = np.zeros((4, 4)) extent = actor_bb.extent x = extent.x * scale_factor y = extent.y * scale_factor z = extent.z * scale_factor cords[0, :] = np.array([x, y, 0, 1]) cords[1, :] = np.array([-x, y, 0, 1]) cords[2, :] = np.array([-x, -y, 0, 1]) cords[3, :] = np.array([x, -y, 0, 1]) return cords def _get_sensor_position(self, cam): """returns the sensor position and rotation Args: cam ([type]): [description] Returns: [type]: [description] """ sensor_transform = self._sensors[cam].get_transform() return sensor_transform def _world_to_sensor(self, cords, sensor, move_cords=False): """ Transforms world coordinates to sensor. """ sensor_world_matrix = self.get_matrix(sensor) world_sensor_matrix = np.linalg.inv(sensor_world_matrix) sensor_cords = np.dot(world_sensor_matrix, cords) if move_cords: _num_cords = range(sensor_cords.shape[1]) modified_cords = np.array([]) for i in _num_cords: if sensor_cords[0,i] < 0: for j in _num_cords: if sensor_cords[0,j] > 0: _direction = sensor_cords[:,i] - sensor_cords[:,j] _distance = -sensor_cords[0,j] / _direction[0] new_cord = sensor_cords[:,j] + _distance[0,0] * _direction * 0.9999 modified_cords = np.hstack([modified_cords, new_cord]) if modified_cords.size else new_cord else: modified_cords = np.hstack([modified_cords, sensor_cords[:,i]]) if modified_cords.size else sensor_cords[:,i] return modified_cords else: return sensor_cords def get_matrix(self, transform): """ Creates matrix from carla transform. """ rotation = transform.rotation location = transform.location c_y = np.cos(np.radians(rotation.yaw)) s_y = np.sin(np.radians(rotation.yaw)) c_r = np.cos(np.radians(rotation.roll)) s_r = np.sin(np.radians(rotation.roll)) c_p = np.cos(np.radians(rotation.pitch)) s_p = np.sin(np.radians(rotation.pitch)) matrix = np.matrix(np.identity(4)) matrix[0, 3] = location.x matrix[1, 3] = location.y matrix[2, 3] = location.z matrix[0, 0] = c_p * c_y matrix[0, 1] = c_y * s_p * s_r - s_y * c_r matrix[0, 2] = -c_y * s_p * c_r - s_y * s_r matrix[1, 0] = s_y * c_p matrix[1, 1] = s_y * s_p * s_r + c_y * c_r matrix[1, 2] = -s_y * s_p * c_r + c_y * s_r matrix[2, 0] = s_p matrix[2, 1] = -c_p * s_r matrix[2, 2] = c_p * c_r return matrix def _change_seg_tl(self, seg_img, depth_img, traffic_lights, _region_size=4): """Adds 3 traffic light classes (green, yellow, red) to the segmentation image Args: seg_img ([type]): [description] depth_img ([type]): [description] traffic_lights ([type]): [description] _region_size (int, optional): [description]. Defaults to 4. """ for tl in traffic_lights: _dist = self._get_distance(tl.get_transform().location) _region = np.abs(depth_img - _dist) if tl.get_state() == carla.TrafficLightState.Red: state = 23 elif tl.get_state() == carla.TrafficLightState.Yellow: state = 24 elif tl.get_state() == carla.TrafficLightState.Green: state = 25 else: #none of the states above, do not change class state = 18 #seg_img[(_region >= _region_size)] = 0 seg_img[(_region < _region_size) & (seg_img == 18)] = state def _get_dist(self, p1, p2): """Returns the distance between p1 and p2 Args: target ([type]): [description] Returns: [type]: [description] """ distance = np.sqrt( (p1[0] - p2[0]) ** 2 + (p1[1] - p2[1]) ** 2 + (p1[2] - p2[2]) ** 2) return distance def _get_distance(self, target): """Returns the distance from the (rgb_front) camera to the target Args: target ([type]): [description] Returns: [type]: [description] """ sensor_transform = self._sensors['rgb_front'].get_transform() distance = np.sqrt( (sensor_transform.location.x - target.x) ** 2 + (sensor_transform.location.y - target.y) ** 2 + (sensor_transform.location.z - target.z) ** 2) return distance def _get_depth(self, data): """Transforms the depth image into meters Args: data ([type]): [description] Returns: [type]: [description] """ data = data.astype(np.float32) normalized = np.dot(data, [65536.0, 256.0, 1.0]) normalized /= (256 * 256 * 256 - 1) in_meters = 1000 * normalized return in_meters def _find_obstacle(self, obstacle_type='*traffic_light*'): """Find all actors of a certain type that are close to the vehicle Args: obstacle_type (str, optional): [description]. Defaults to '*traffic_light*'. Returns: [type]: [description] """ obst = list() _actors = self._world.get_actors() _obstacles = _actors.filter(obstacle_type) for _obstacle in _obstacles: trigger = _obstacle.trigger_volume _obstacle.get_transform().transform(trigger.location) distance_to_car = trigger.location.distance(self._vehicle.get_location()) a = np.sqrt( trigger.extent.x ** 2 + trigger.extent.y ** 2 + trigger.extent.z ** 2) b = np.sqrt( self._vehicle.bounding_box.extent.x ** 2 + self._vehicle.bounding_box.extent.y ** 2 + self._vehicle.bounding_box.extent.z ** 2) s = a + b + 10 if distance_to_car <= s: # the actor is affected by this obstacle. obst.append(_obstacle) return obst def _get_camera_to_car_calibration(self, sensor): """returns the calibration matrix for the given sensor Args: sensor ([type]): [description] Returns: [type]: [description] """ calibration = np.identity(3) calibration[0, 2] = sensor["width"] / 2.0 calibration[1, 2] = sensor["height"] / 2.0 calibration[0, 0] = calibration[1, 1] = sensor["width"] / (2.0 * np.tan(sensor["fov"] * np.pi / 360.0)) return calibration ================================================ FILE: leaderboard/team_code/map_agent.py ================================================ import numpy as np from PIL import Image, ImageDraw from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from team_code.base_agent import BaseAgent from team_code.planner import RoutePlanner class MapAgent(BaseAgent): def sensors(self): result = super().sensors() result.append({ 'type': 'sensor.camera.semantic_segmentation', 'x': 0.0, 'y': 0.0, 'z': 100.0, 'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0, 'width': 512, 'height': 512, 'fov': 5 * 10.0, 'id': 'map' }) return result def set_global_plan(self, global_plan_gps, global_plan_world_coord, wp=None): super().set_global_plan(global_plan_gps, global_plan_world_coord) self._plan_HACK = global_plan_world_coord self._plan_gps_HACK = global_plan_gps def _init(self): super()._init() self._vehicle = CarlaDataProvider.get_hero_actor() self._world = self._vehicle.get_world() self._waypoint_planner = RoutePlanner(4.0, 50) self._waypoint_planner.set_route(self._plan_gps_HACK, True) self._traffic_lights = list() def tick(self, input_data): self._actors = self._world.get_actors() self._traffic_lights = get_nearby_lights(self._vehicle, self._actors.filter('*traffic_light*')) self._stop_signs = get_nearby_lights(self._vehicle, self._actors.filter('*stop*')) topdown = input_data['map'][1][:, :, 2] topdown = draw_traffic_lights(topdown, self._vehicle, self._traffic_lights) topdown = draw_stop_signs(topdown, self._vehicle, self._stop_signs) result = super().tick(input_data) result['topdown'] = topdown return result def get_nearby_lights(vehicle, lights, pixels_per_meter=5.5, size=512, radius=5): result = list() transform = vehicle.get_transform() pos = transform.location theta = np.radians(90 + transform.rotation.yaw) R = np.array([ [np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)], ]) for light in lights: delta = light.get_transform().location - pos target = R.T.dot([delta.x, delta.y]) target *= pixels_per_meter target += size // 2 if min(target) < 0 or max(target) >= size: continue trigger = light.trigger_volume light.get_transform().transform(trigger.location) dist = trigger.location.distance(vehicle.get_location()) a = np.sqrt( trigger.extent.x ** 2 + trigger.extent.y ** 2 + trigger.extent.z ** 2) b = np.sqrt( vehicle.bounding_box.extent.x ** 2 + vehicle.bounding_box.extent.y ** 2 + vehicle.bounding_box.extent.z ** 2) if dist > a + b: continue result.append(light) return result def draw_traffic_lights(image, vehicle, lights, pixels_per_meter=5.5, size=512, radius=5): image = Image.fromarray(image) draw = ImageDraw.Draw(image) transform = vehicle.get_transform() pos = transform.location theta = np.radians(90 + transform.rotation.yaw) R = np.array([ [np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)], ]) for light in lights: delta = light.get_transform().location - pos target = R.T.dot([delta.x, delta.y]) target *= pixels_per_meter target += size // 2 if min(target) < 0 or max(target) >= size: continue trigger = light.trigger_volume light.get_transform().transform(trigger.location) dist = trigger.location.distance(vehicle.get_location()) a = np.sqrt( trigger.extent.x ** 2 + trigger.extent.y ** 2 + trigger.extent.z ** 2) b = np.sqrt( vehicle.bounding_box.extent.x ** 2 + vehicle.bounding_box.extent.y ** 2 + vehicle.bounding_box.extent.z ** 2) if dist > a + b: continue x, y = target draw.ellipse((x-radius, y-radius, x+radius, y+radius), 23 + light.state.real) # 13 changed to 23 for carla 0.9.10 return np.array(image) def draw_stop_signs(image, vehicle, lights, pixels_per_meter=5.5, size=512, radius=5): image = Image.fromarray(image) draw = ImageDraw.Draw(image) transform = vehicle.get_transform() pos = transform.location theta = np.radians(90 + transform.rotation.yaw) R = np.array([ [np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)], ]) for light in lights: delta = light.get_transform().location - pos target = R.T.dot([delta.x, delta.y]) target *= pixels_per_meter target += size // 2 if min(target) < 0 or max(target) >= size: continue trigger = light.trigger_volume light.get_transform().transform(trigger.location) dist = trigger.location.distance(vehicle.get_location()) a = np.sqrt( trigger.extent.x ** 2 + trigger.extent.y ** 2 + trigger.extent.z ** 2) b = np.sqrt( vehicle.bounding_box.extent.x ** 2 + vehicle.bounding_box.extent.y ** 2 + vehicle.bounding_box.extent.z ** 2) if dist > a + b: continue x, y = target draw.ellipse((x-radius, y-radius, x+radius, y+radius), 26) return np.array(image) ================================================ FILE: leaderboard/team_code/pid_controller.py ================================================ from collections import deque import numpy as np class PIDController(object): def __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20): self._K_P = K_P self._K_I = K_I self._K_D = K_D self._window = deque([0 for _ in range(n)], maxlen=n) self._max = 0.0 self._min = 0.0 def step(self, error): self._window.append(error) self._max = max(self._max, abs(error)) self._min = -abs(self._max) if len(self._window) >= 2: integral = np.mean(self._window) derivative = (self._window[-1] - self._window[-2]) else: integral = 0.0 derivative = 0.0 return self._K_P * error + self._K_I * integral + self._K_D * derivative ================================================ FILE: leaderboard/team_code/planner.py ================================================ import os from collections import deque import numpy as np DEBUG = int(os.environ.get('HAS_DISPLAY', 0)) class Plotter(object): def __init__(self, size): self.size = size self.clear() self.title = str(self.size) def clear(self): from PIL import Image, ImageDraw self.img = Image.fromarray(np.zeros((self.size, self.size, 3), dtype=np.uint8)) self.draw = ImageDraw.Draw(self.img) def dot(self, pos, node, color=(255, 255, 255), r=2): x, y = 5.5 * (pos - node) x += self.size / 2 y += self.size / 2 self.draw.ellipse((x-r, y-r, x+r, y+r), color) def show(self): if not DEBUG: return import cv2 cv2.imshow(self.title, cv2.cvtColor(np.array(self.img), cv2.COLOR_BGR2RGB)) cv2.waitKey(1) class RoutePlanner(object): def __init__(self, min_distance, max_distance, debug_size=256): self.route = deque() self.min_distance = min_distance self.max_distance = max_distance # self.mean = np.array([49.0, 8.0]) # for carla 9.9 # self.scale = np.array([111324.60662786, 73032.1570362]) # for carla 9.9 self.mean = np.array([0.0, 0.0]) # for carla 9.10 self.scale = np.array([111324.60662786, 111319.490945]) # for carla 9.10 self.debug = Plotter(debug_size) def set_route(self, global_plan, gps=False, global_plan_world = None): self.route.clear() if global_plan_world: for (pos, cmd), (pos_word, _ )in zip(global_plan, global_plan_world): if gps: pos = np.array([pos['lat'], pos['lon']]) pos -= self.mean pos *= self.scale else: pos = np.array([pos.location.x, pos.location.y]) pos -= self.mean self.route.append((pos, cmd, pos_word)) else: for pos, cmd in global_plan: if gps: pos = np.array([pos['lat'], pos['lon']]) pos -= self.mean pos *= self.scale else: pos = np.array([pos.location.x, pos.location.y]) pos -= self.mean self.route.append((pos, cmd)) def run_step(self, gps): self.debug.clear() if len(self.route) == 1: return self.route[0] to_pop = 0 farthest_in_range = -np.inf cumulative_distance = 0.0 for i in range(1, len(self.route)): if cumulative_distance > self.max_distance: break cumulative_distance += np.linalg.norm(self.route[i][0] - self.route[i-1][0]) distance = np.linalg.norm(self.route[i][0] - gps) if distance <= self.min_distance and distance > farthest_in_range: farthest_in_range = distance to_pop = i r = 255 * int(distance > self.min_distance) g = 255 * int(self.route[i][1].value == 4) b = 255 self.debug.dot(gps, self.route[i][0], (r, g, b)) for _ in range(to_pop): if len(self.route) > 2: self.route.popleft() self.debug.dot(gps, self.route[0][0], (0, 255, 0)) self.debug.dot(gps, self.route[1][0], (255, 0, 0)) self.debug.dot(gps, gps, (0, 0, 255)) self.debug.show() return self.route[1] ================================================ FILE: leaderboard/team_code/roach_ap_agent_data_collection.py ================================================ import os import carla import json import datetime import pathlib import time import cv2 from collections import deque import random import torch import numpy as np from PIL import Image from leaderboard.autoagents import autonomous_agent import numpy as np from omegaconf import OmegaConf import copy from roach.criteria import run_stop_sign from roach.obs_manager.birdview.chauffeurnet import ObsManager from roach.utils.config_utils import load_entry_point import roach.utils.transforms as trans_utils from roach.utils.expert_noiser import ExpertNoiser from roach.utils.traffic_light import TrafficLightHandler import io from io import BytesIO def array_to_bytes(x: np.ndarray) -> bytes: np_bytes = BytesIO() np.save(np_bytes, x, allow_pickle=True) return np_bytes.getvalue() def bytes_to_array(b: bytes) -> np.ndarray: np_bytes = BytesIO(b) return np.load(np_bytes, allow_pickle=True) from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from leaderboard.utils.route_manipulation import downsample_route from agents.navigation.local_planner import RoadOption from team_code.planner import RoutePlanner def np_encoder(object): if isinstance(object, np.generic): return object.item() SAVE_PATH = os.environ.get('SAVE_PATH', None) conf_path = '~/petreloss.conf' def get_entry_point(): return 'ROACHAgent' def _numpy(carla_vector, normalize=False): result = np.float32([carla_vector.x, carla_vector.y]) if normalize: return result / (np.linalg.norm(result) + 1e-4) return result def _location(x, y, z): return carla.Location(x=float(x), y=float(y), z=float(z)) def get_xyz(_): return np.array([_.x, _.y, _.z]) def _orientation(yaw): return np.float32([np.cos(np.radians(yaw)), np.sin(np.radians(yaw))]) def get_collision(p1, v1, p2, v2): A = np.stack([v1, -v2], 1) b = p2 - p1 if abs(np.linalg.det(A)) < 1e-3: return False, None x = np.linalg.solve(A, b) collides = all(x >= 0) and all(x <= 1) # how many seconds until collision return collides, p1 + x[0] * v1 def get_nearby_object(vehicle_position, actor_list, radius): nearby_objects = [] for actor in actor_list: trigger_box_global_pos = actor.get_transform().transform(actor.trigger_volume.location) trigger_box_global_pos = carla.Location(x=trigger_box_global_pos.x, y=trigger_box_global_pos.y, z=trigger_box_global_pos.z) if (trigger_box_global_pos.distance(vehicle_position) < radius): nearby_objects.append(actor) return nearby_objects class ROACHAgent(autonomous_agent.AutonomousAgent): def setup(self, path_to_conf_file, ckpt="roach/log/ckpt_11833344.pth"): self.is_local = (os.environ['IS_LOCAL'] == "True") ## Ignore non-local situation since we collect data in a cluster with ceph if not self.is_local: from petrel_client.client import Client self.client = Client(conf_path) self._render_dict = None self.supervision_dict = None self._ckpt = ckpt cfg = OmegaConf.load(path_to_conf_file) cfg = OmegaConf.to_container(cfg) self.cfg = cfg self._obs_configs = cfg['obs_configs'] self._train_cfg = cfg['training'] self._policy_class = load_entry_point(cfg['policy']['entry_point']) self._policy_kwargs = cfg['policy']['kwargs'] if self._ckpt is None: self._policy = None else: self._policy, self._train_cfg['kwargs'] = self._policy_class.load(self._ckpt) self._policy = self._policy.eval() self._wrapper_class = load_entry_point(cfg['env_wrapper']['entry_point']) self._wrapper_kwargs = cfg['env_wrapper']['kwargs'] self.track = autonomous_agent.Track.SENSORS self.config_path = path_to_conf_file self.step = -1 self.wall_start = time.time() self.initialized = False self.prev_lidar = None ## The frequency of lidar is 10 Hz while the frequency of simulation is 20Hz -> In each frame, the sensor only returns half lidar points. self._active_traffic_light = None self.save_path = None if SAVE_PATH is not None: now = datetime.datetime.now() time_string = '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second))) string = pathlib.Path(os.environ['ROUTES']).stem + '_' string += time_string if self.is_local: self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string self.save_path.mkdir(parents=True, exist_ok=False) (self.save_path / '3d_bbs').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_front').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_left').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_right').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_back').mkdir(parents=True, exist_ok=True) (self.save_path / 'seg_front').mkdir(parents=True, exist_ok=True) (self.save_path / 'seg_left').mkdir(parents=True, exist_ok=True) (self.save_path / 'seg_right').mkdir(parents=True, exist_ok=True) (self.save_path / 'seg_back').mkdir(parents=True, exist_ok=True) (self.save_path / 'depth_front').mkdir(parents=True, exist_ok=True) (self.save_path / 'depth_left').mkdir(parents=True, exist_ok=True) (self.save_path / 'depth_right').mkdir(parents=True, exist_ok=True) (self.save_path / 'depth_back').mkdir(parents=True, exist_ok=True) (self.save_path / 'lidar').mkdir(parents=True, exist_ok=True) (self.save_path / 'measurements').mkdir() (self.save_path / 'supervision').mkdir() (self.save_path / 'bev').mkdir() ## Visualization of Scene for debug (self.save_path / 'bev_seg_label').mkdir() else: ## Ignore non-local situation since we collect data in a cluster with ceph self.save_path = "s3://CarlaData/Multiple/" + os.environ['ROUTE_FILE'] + "/" + string self.folder_name = string def _init(self): self._waypoint_planner = RoutePlanner(4.0, 50) self._waypoint_planner.set_route(self._plan_gps_HACK, True) self._command_planner = RoutePlanner(7.5, 25.0, 257) self._command_planner.set_route(self._global_plan, True) self._route_planner = RoutePlanner(4.0, 50.0) self._route_planner.set_route(self._global_plan, True) self._world = CarlaDataProvider.get_world() self._map = self._world.get_map() self._ego_vehicle = CarlaDataProvider.get_ego() self._last_route_location = self._ego_vehicle.get_location() self._criteria_stop = run_stop_sign.RunStopSign(self._world) self.birdview_obs_manager = ObsManager(self.cfg['obs_configs']['birdview'], self._criteria_stop) self.birdview_obs_manager.attach_ego_vehicle(self._ego_vehicle) self.navigation_idx = -1 # for stop signs self._target_stop_sign = None # the stop sign affecting the ego vehicle self._stop_completed = False # if the ego vehicle has completed the stop sign self._affected_by_stop = False # if the ego vehicle is influenced by a stop sign TrafficLightHandler.reset(self._world) print("initialized") self.initialized = True def _get_angle_to(self, pos, theta, target): R = np.array([ [np.cos(theta), -np.sin(theta)], [np.sin(theta), np.cos(theta)], ]) aim = R.T.dot(target - pos) angle = -np.degrees(np.arctan2(-aim[1], aim[0])) angle = 0.0 if np.isnan(angle) else angle return angle def _truncate_global_route_till_local_target(self, windows_size=5): ev_location = self._ego_vehicle.get_location() closest_idx = 0 for i in range(len(self._global_route)-1): if i > windows_size: break loc0 = self._global_route[i][0].transform.location loc1 = self._global_route[i+1][0].transform.location wp_dir = loc1 - loc0 wp_veh = ev_location - loc0 dot_ve_wp = wp_veh.x * wp_dir.x + wp_veh.y * wp_dir.y + wp_veh.z * wp_dir.z if dot_ve_wp > 0: closest_idx = i+1 if closest_idx > 0: self._last_route_location = carla.Location(self._global_route[0][0].transform.location) self._global_route = self._global_route[closest_idx:] def _get_position(self, tick_data): gps = tick_data['gps'] gps = (gps - self._command_planner.mean) * self._command_planner.scale return gps def set_global_plan(self, global_plan_gps, global_plan_world_coord, wp_route): """ Set the plan (route) for the agent """ self._global_route = wp_route ds_ids = downsample_route(global_plan_world_coord, 50) self._global_plan = [global_plan_gps[x] for x in ds_ids] self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1]) for x in ds_ids] self._plan_gps_HACK = global_plan_gps self._plan_HACK = global_plan_world_coord def sensors(self): return [ { 'type': 'sensor.camera.rgb', 'x': 1.5, 'y': 0.0, 'z':2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_front' }, { 'type': 'sensor.camera.rgb', 'x': 0, 'y': -0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_left' }, { 'type': 'sensor.camera.rgb', 'x': 0, 'y': 0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_right' }, { 'type': 'sensor.camera.rgb', 'x': -1.6, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_back' }, { 'type': 'sensor.camera.semantic_segmentation', 'x': 1.3, 'y': 0.0, 'z':2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'seg_front' }, { 'type': 'sensor.camera.semantic_segmentation', 'x': 0, 'y': -0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'seg_left' }, { 'type': 'sensor.camera.semantic_segmentation', 'x': 0, 'y': 0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'seg_right' }, { 'type': 'sensor.camera.semantic_segmentation', 'x': -1.6, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'seg_back' }, { 'type': 'sensor.camera.depth', 'x': 1.3, 'y': 0.0, 'z':2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'depth_front' }, { 'type': 'sensor.camera.depth', 'x': 0, 'y': -0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'depth_left' }, { 'type': 'sensor.camera.depth', 'x': 0, 'y': 0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'depth_right' }, { 'type': 'sensor.camera.depth', 'x': -1.6, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'depth_back' }, { 'type': 'sensor.lidar.ray_cast', 'x': 0.0, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'id': 'lidar' }, { 'type': 'sensor.other.imu', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.05, 'id': 'imu' }, { 'type': 'sensor.other.gnss', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.01, 'id': 'gps' }, { 'type': 'sensor.speedometer', 'reading_frequency': 20, 'id': 'speed' } ] def tick(self, input_data, timestamp): self._truncate_global_route_till_local_target() birdview_obs = self.birdview_obs_manager.get_observation(self._global_route) control = self._ego_vehicle.get_control() throttle = np.array([control.throttle], dtype=np.float32) steer = np.array([control.steer], dtype=np.float32) brake = np.array([control.brake], dtype=np.float32) gear = np.array([control.gear], dtype=np.float32) ev_transform = self._ego_vehicle.get_transform() vel_w = self._ego_vehicle.get_velocity() vel_ev = trans_utils.vec_global_to_ref(vel_w, ev_transform.rotation) vel_xy = np.array([vel_ev.x, vel_ev.y], dtype=np.float32) self._criteria_stop.tick(self._ego_vehicle, timestamp) state_list = [] state_list.append(throttle) state_list.append(steer) state_list.append(brake) state_list.append(gear) state_list.append(vel_xy) state = np.concatenate(state_list) obs_dict = { 'state': state.astype(np.float32), 'birdview': birdview_obs['masks'], } # Roach Input: Road Mask - 0, Route Mask - 1, Lane_Mask (broken lane - 0.5) -2, 4 * vehicle - 3456, 4 * walker, 4 * traffic_light [-16, -11, -6, -1] 10hz bev_seg_label = birdview_obs['masks'].copy().astype(np.float32)/255.0 rgb_front = cv2.cvtColor(input_data['rgb_front'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_left = cv2.cvtColor(input_data['rgb_left'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_right = cv2.cvtColor(input_data['rgb_right'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_back = cv2.cvtColor(input_data['rgb_back'][1][:, :, :3], cv2.COLOR_BGR2RGB) gps = input_data['gps'][1][:2] speed = input_data['speed'][1]['speed'] compass = input_data['imu'][1][-1] acceleration = input_data['imu'][1][:3] angular_velocity = input_data['imu'][1][3:6] target_gps, target_command = self.get_target_gps(input_data['gps'][1], compass) weather = self._weather_to_dict(self._world.get_weather()) seg_front = np.copy(input_data["seg_front"][1][:, :, 2]) seg_left = np.copy(input_data["seg_left"][1][:, :, 2]) seg_right = np.copy(input_data["seg_right"][1][:, :, 2]) seg_back = np.copy(input_data["seg_back"][1][:, :, 2]) depth_front = cv2.cvtColor(input_data['depth_front'][1][:, :, :3], cv2.COLOR_BGR2RGB) depth_left = cv2.cvtColor(input_data['depth_left'][1][:, :, :3], cv2.COLOR_BGR2RGB) depth_right = cv2.cvtColor(input_data['depth_right'][1][:, :, :3], cv2.COLOR_BGR2RGB) depth_back = cv2.cvtColor(input_data['depth_back'][1][:, :, :3], cv2.COLOR_BGR2RGB) result = { 'rgb_front': rgb_front, 'rgb_left': rgb_left, 'rgb_right': rgb_right, 'rgb_back': rgb_back, 'seg_front': seg_front, 'seg_left': seg_left, 'seg_right': seg_right, 'seg_back': seg_back, 'depth_front': depth_front, 'depth_left': depth_left, 'depth_right': depth_right, 'depth_back': depth_back, 'lidar' : input_data['lidar'][1], 'gps': gps, 'speed': speed, 'compass': compass, 'weather': weather, "acceleration":acceleration, "angular_velocity":angular_velocity, "bev_seg_label": bev_seg_label } next_wp, next_cmd = self._route_planner.run_step(self._get_position(result)) result['next_command'] = next_cmd.value result['x_target'] = next_wp[0] result['y_target'] = next_wp[1] return result, obs_dict, birdview_obs['rendered'], target_gps, target_command, None def im_render(self, render_dict): im_birdview = render_dict['rendered'] h, w, c = im_birdview.shape im = np.zeros([h, w*2, c], dtype=np.uint8) im[:h, :w] = im_birdview action_str = np.array2string(render_dict['action'], precision=2, separator=',', suppress_small=True) txt_1 = f'a{action_str}' im = cv2.putText(im, txt_1, (3, 24), cv2.FONT_HERSHEY_SIMPLEX, 0.3, (255, 255, 255), 1) debug_texts = [ 'should_brake: ' + render_dict['should_brake'], ] for i, txt in enumerate(debug_texts): im = cv2.putText(im, txt, (w, (i+2)*12), cv2.FONT_HERSHEY_SIMPLEX, 0.3, (255, 255, 255), 1) return im @torch.no_grad() def run_step(self, input_data, timestamp): if not self.initialized: self._init() self.step += 1 if self.step < 20: control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 self.last_control = control self.prev_lidar = input_data['lidar'][1] self.prev_matrix = self._ego_vehicle.get_transform().get_matrix() return control if self.step % 2 != 0: self.prev_lidar = input_data['lidar'][1] self.prev_matrix = self._ego_vehicle.get_transform().get_matrix() return self.last_control tick_data, policy_input, rendered, target_gps, target_command, _ = self.tick(input_data, timestamp) gps = self._get_position(tick_data) near_node, near_command = self._waypoint_planner.run_step(gps) far_node, far_command = self._command_planner.run_step(gps) ## Roach forward actions, values, log_probs, mu, sigma, features, cnn_feature = self._policy.forward( policy_input, deterministic=True, clip_action=True) control = self.process_act(actions) render_dict = {"rendered": rendered, "action": actions} ## Rules for emergency brake should_brake = self.collision_detect() only_ap_brake = True if (control.brake <= 0 and should_brake) else False if should_brake: control.steer = control.steer * 0.5 control.throttle = 0.0 control.brake = 1.0 render_dict = {"rendered": rendered, "action": actions, "should_brake":str(should_brake),} render_img = self.im_render(render_dict) supervision_dict = { 'action': np.array([control.throttle, control.steer, control.brake], dtype=np.float32), 'value': values[0], 'action_mu': mu[0], 'action_sigma': sigma[0], 'features': features[0], 'cnn_features':cnn_feature, 'speed': tick_data['speed'], 'target_gps': target_gps, 'target_command': target_command, 'should_brake': should_brake, 'only_ap_brake': only_ap_brake, } if SAVE_PATH is not None and self.step % 10 == 0: self.save(near_node, far_node, near_command, far_command, tick_data, supervision_dict, render_img, should_brake) steer = control.steer control.steer = steer + 1e-2 * np.random.randn() ## Random noise for robustness self.last_control = control self.prev_lidar = input_data['lidar'][1] self.prev_matrix = self._ego_vehicle.get_transform().get_matrix() return control def collision_detect(self): actors = self._world.get_actors() vehicle = self._is_vehicle_hazard(actors.filter('*vehicle*')) walker = self._is_walker_hazard(actors.filter('*walker*')) self.is_vehicle_present = 1 if vehicle is not None else 0 self.is_pedestrian_present = 1 if walker is not None else 0 return any(x is not None for x in [vehicle, walker]) def _is_walker_hazard(self, walkers_list): z = self._ego_vehicle.get_location().z p1 = _numpy(self._ego_vehicle.get_location()) v1 = 10.0 * _orientation(self._ego_vehicle.get_transform().rotation.yaw) for walker in walkers_list: v2_hat = _orientation(walker.get_transform().rotation.yaw) s2 = np.linalg.norm(_numpy(walker.get_velocity())) if s2 < 0.05: v2_hat *= s2 p2 = -3.0 * v2_hat + _numpy(walker.get_location()) v2 = 8.0 * v2_hat collides, collision_point = get_collision(p1, v1, p2, v2) if collides: return walker return None def _is_vehicle_hazard(self, vehicle_list): z = self._ego_vehicle.get_location().z o1 = _orientation(self._ego_vehicle.get_transform().rotation.yaw) p1 = _numpy(self._ego_vehicle.get_location()) s1 = max(10, 3.0 * np.linalg.norm(_numpy(self._ego_vehicle.get_velocity()))) # increases the threshold distance v1_hat = o1 v1 = s1 * v1_hat for target_vehicle in vehicle_list: if target_vehicle.id == self._ego_vehicle.id: continue o2 = _orientation(target_vehicle.get_transform().rotation.yaw) p2 = _numpy(target_vehicle.get_location()) s2 = max(5.0, 2.0 * np.linalg.norm(_numpy(target_vehicle.get_velocity()))) v2_hat = o2 v2 = s2 * v2_hat p2_p1 = p2 - p1 distance = np.linalg.norm(p2_p1) p2_p1_hat = p2_p1 / (distance + 1e-4) angle_to_car = np.degrees(np.arccos(v1_hat.dot(p2_p1_hat))) angle_between_heading = np.degrees(np.arccos(o1.dot(o2))) # to consider -ve angles too angle_to_car = min(angle_to_car, 360.0 - angle_to_car) angle_between_heading = min(angle_between_heading, 360.0 - angle_between_heading) if angle_between_heading > 60.0 and not (angle_to_car < 15 and distance < s1): continue elif angle_to_car > 30.0: continue elif distance > s1: continue return target_vehicle return None def save(self, near_node, far_node, near_command, far_command, tick_data, supervision_dict, render_img, should_brake): frame = self.step // 10 - 2 if self.is_local: Image.fromarray(tick_data['rgb_front']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame)) Image.fromarray(tick_data['rgb_left']).save(self.save_path / 'rgb_left' / ('%04d.png' % frame)) Image.fromarray(tick_data['rgb_right']).save(self.save_path / 'rgb_right' / ('%04d.png' % frame)) Image.fromarray(tick_data['rgb_back']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame)) Image.fromarray(tick_data['seg_front']).save(self.save_path / 'seg_front' / ('%04d.png' % frame)) Image.fromarray(tick_data['seg_left']).save(self.save_path / 'seg_left' / ('%04d.png' % frame)) Image.fromarray(tick_data['seg_right']).save(self.save_path / 'seg_right' / ('%04d.png' % frame)) Image.fromarray(tick_data['seg_back']).save(self.save_path / 'seg_back' / ('%04d.png' % frame)) Image.fromarray(tick_data['depth_front']).save(self.save_path / 'depth_front' / ('%04d.png' % frame)) Image.fromarray(tick_data['depth_left']).save(self.save_path / 'depth_left' / ('%04d.png' % frame)) Image.fromarray(tick_data['depth_right']).save(self.save_path / 'depth_right' / ('%04d.png' % frame)) Image.fromarray(tick_data['depth_back']).save(self.save_path / 'depth_back' / ('%04d.png' % frame)) Image.fromarray(render_img).save(self.save_path / 'bev' / ('%04d.png' % frame)) np.save(self.save_path / 'bev_seg_label' / ('%04d.npy' % frame), tick_data['bev_seg_label'], allow_pickle=True) with open(self.save_path / 'supervision' / ('%04d.npy' % frame), 'wb') as f: np.save(f, supervision_dict) else: for key_name in ["rgb_front", "rgb_left", "rgb_right", "rgb_back", "seg_front", "seg_left", "seg_right", "seg_back", "depth_front", "depth_left", "depth_right", "depth_back", "topdown"]: self.client.put(os.path.join(self.save_path, key_name, '%04d.png' % frame), tick_data[key_name].tostring()) self.client.put(os.path.join(self.save_path, "bev_seg_label", '%04d.npy' % frame), tick_data['bev_seg_label'].tostring()) self.client.put(os.path.join(self.save_path, "supervision", '%04d.npy' % frame), array_to_bytes(supervision_dict)) current_inv_mat = np.array(self._ego_vehicle.get_transform().get_inverse_matrix()) relative_transform_mat = np.dot(current_inv_mat , np.array(self.prev_matrix)) #4 * 4 transformed_prev_lidar_xyz = np.concatenate([self.prev_lidar[:, :3], np.ones((self.prev_lidar.shape[0], 1))], axis=1) # N * 4 transformed_prev_lidar_xyz = np.einsum("ij,kj->ki", relative_transform_mat, transformed_prev_lidar_xyz) transformed_prev_lidar_xyz = np.concatenate([transformed_prev_lidar_xyz[:, :3], self.prev_lidar[:, 3][:, np.newaxis]], axis=1) saved_lidar = np.concatenate([transformed_prev_lidar_xyz, tick_data['lidar']], axis=0) saved_lidar[:, 2] += 2.5 #offset lidar z actor_lis = self._get_3d_bbs(lidar=saved_lidar, max_distance=50) pos = self._get_position(tick_data) theta = tick_data['compass'] speed = tick_data['speed'] weather = tick_data['weather'] data = { 'x': pos[0], 'y': pos[1], 'theta': theta, 'speed': speed, 'x_command_far': far_node[0], 'y_command_far': far_node[1], 'command_far': far_command.value, 'x_command_near': near_node[0], 'y_command_near': near_node[1], 'command_near': near_command.value, 'should_brake': should_brake, 'x_target': tick_data['x_target'], 'y_target': tick_data['y_target'],'target_command': tick_data['next_command'], 'weather': weather, "acceleration":tick_data["acceleration"].tolist(), "angular_velocity":tick_data["angular_velocity"].tolist() } if self.is_local: outfile = open(self.save_path / '3d_bbs' / ('%04d.json' % frame), 'w') json.dump(actor_lis, outfile, indent=4, default=np_encoder) outfile.close() outfile = open(self.save_path / 'measurements' / ('%04d.json' % frame), 'w') json.dump(data, outfile, indent=4) outfile.close() np.save(self.save_path / 'lidar' / ('%04d.npy' % frame), saved_lidar.astype(np.float32), allow_pickle=True) else: self.client.put(os.path.join(self.save_path, '3d_bbs', '%04d.json' % frame), json.dumps(actor_lis, default=np_encoder).encode('utf-8')) self.client.put(os.path.join(self.save_path, 'measurements', '%04d.json' % frame), json.dumps(data, default=np_encoder).encode('utf-8')) self.client.put(os.path.join(self.save_path, 'lidar', '%04d.npy' % frame), array_to_bytes(saved_lidar)) def get_target_gps(self, gps, compass): # target gps def gps_to_location(gps): lat, lon, z = gps lat = float(lat) lon = float(lon) z = float(z) location = carla.Location(z=z) xy = (gps[:2] - self._command_planner.mean) * self._command_planner.scale location.x = xy[0] location.y = -xy[1] ## Dose not matter, because no explicit judge left or right return location global_plan_gps = self._global_plan next_gps, _ = global_plan_gps[self.navigation_idx+1] next_gps = np.array([next_gps['lat'], next_gps['lon'], next_gps['z']]) next_vec_in_global = gps_to_location(next_gps) - gps_to_location(gps) ref_rot_in_global = carla.Rotation(yaw=np.rad2deg(compass)-90.0) loc_in_ev = trans_utils.vec_global_to_ref(next_vec_in_global, ref_rot_in_global) if np.sqrt(loc_in_ev.x**2+loc_in_ev.y**2) < 12.0 and loc_in_ev.x < 0.0: self.navigation_idx += 1 self.navigation_idx = min(self.navigation_idx, len(global_plan_gps)-2) _, road_option_0 = global_plan_gps[max(0, self.navigation_idx)] gps_point, road_option_1 = global_plan_gps[self.navigation_idx+1] gps_point = np.array([gps_point['lat'], gps_point['lon'], gps_point['z']]) if (road_option_0 in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]) \ and (road_option_1 not in [RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT]): road_option = road_option_1 else: road_option = road_option_0 return np.array(gps_point, dtype=np.float32), np.array([road_option.value], dtype=np.int8) def process_act(self, action): acc = action[0][0] steer = action[0][1] if acc >= 0.0: throttle = acc brake = 0.0 else: throttle = 0.0 brake = np.abs(acc) throttle = np.clip(throttle, 0, 1) steer = np.clip(steer, -1, 1) brake = np.clip(brake, 0, 1) control = carla.VehicleControl(throttle=throttle, steer=steer, brake=brake) return control def _weather_to_dict(self, carla_weather): weather = { 'cloudiness': carla_weather.cloudiness, 'precipitation': carla_weather.precipitation, 'precipitation_deposits': carla_weather.precipitation_deposits, 'wind_intensity': carla_weather.wind_intensity, 'sun_azimuth_angle': carla_weather.sun_azimuth_angle, 'sun_altitude_angle': carla_weather.sun_altitude_angle, 'fog_density': carla_weather.fog_density, 'fog_distance': carla_weather.fog_distance, 'wetness': carla_weather.wetness, 'fog_falloff': carla_weather.fog_falloff, } return weather def _get_forward_speed(self, transform=None, velocity=None): """ Convert the vehicle transform directly to forward speed """ if not velocity: velocity = self._ego_vehicle.get_velocity() if not transform: transform = self._ego_vehicle.get_transform() vel_np = np.array([velocity.x, velocity.y, velocity.z]) pitch = np.deg2rad(transform.rotation.pitch) yaw = np.deg2rad(transform.rotation.yaw) orientation = np.array([np.cos(pitch) * np.cos(yaw), np.cos(pitch) * np.sin(yaw), np.sin(pitch)]) speed = np.dot(vel_np, orientation) return speed def get_points_in_bbox(self, ego_mat, vec_inv_mat, dx, lidar): transform_mat = np.dot(vec_inv_mat, ego_mat) lidar = np.concatenate([lidar[:, :3], np.ones((lidar.shape[0], 1))], axis=1) lidar = np.einsum("ij,kj->ki", transform_mat, lidar) # check points in bbox x, y, z = dx / 2. num_points = ((lidar[:, 0] < x) & (lidar[:, 0] > -x) & (lidar[:, 1] < y) & (lidar[:, 1] > -y) & (lidar[:, 2] < z) & (lidar[:, 2] > -z)).sum() return num_points def _get_3d_bbs(self, lidar=None, max_distance=50): results = [] ego_rotation = self._ego_vehicle.get_transform().rotation ego_matrix = np.array(self._ego_vehicle.get_transform().get_matrix()).astype(np.float32) ego_extent = self._ego_vehicle.bounding_box.extent ego_dx = np.array([ego_extent.x, ego_extent.y, ego_extent.z]).astype(np.float32) * 2. ego_yaw = ego_rotation.yaw/180.0*np.pi # also add ego box for visulization relative_rotation = [0, 0, 0] relative_pos = [0, 0, 0] # add vehicle velocity and brake flag ego_transform = self._ego_vehicle.get_transform() ego_control = self._ego_vehicle.get_control() ego_velocity = self._ego_vehicle.get_velocity() ego_speed = self._get_forward_speed(transform=ego_transform, velocity=ego_velocity) # In m/s ego_brake = ego_control.brake ego_inv_mat = np.array(self._ego_vehicle.get_transform().get_inverse_matrix()).astype(np.float32) ego_loc = self._ego_vehicle.get_location() # the position is in lidar coordinates result = {"class": "vehicle", "extent": [ego_dx[0], ego_dx[1], ego_dx[2],], "relative_position": [relative_pos[0], relative_pos[1], relative_pos[2]], #roll pitch yaw "relative_rotation": relative_rotation, "yaw":ego_yaw, "num_points": -1, "distance": -1, "speed": ego_speed, "brake": ego_brake, "id": int(self._ego_vehicle.id), 'ego_matrix': ego_matrix.tolist(), "ego_inv_matrix": ego_inv_mat.tolist(), } results = {} results["ego"] = result results["vehicle"+str(self._ego_vehicle.id)] = result self._actors = self._world.get_actors() for actor_type in ["vehicle", "walker", "traffic_light", "stop"]: selected_actors = self._actors.filter('*' + actor_type + '*') for selected_actor in selected_actors: if (selected_actor.get_location().distance(ego_loc) < max_distance): if (actor_type != "vehicle") or (selected_actor.id != self._ego_vehicle.id): selected_actor_rotation = selected_actor.get_transform().rotation selected_actor_matrix = np.array(selected_actor.get_transform().get_matrix()) selected_actor_inv_matrix = np.array(selected_actor.get_transform().get_inverse_matrix()) selected_actor_id = selected_actor.id if hasattr(selected_actor, 'bounding_box'): selected_actor_extent = selected_actor.bounding_box.extent dx = np.array([selected_actor_extent.x, selected_actor_extent.y, selected_actor_extent.z]).astype(np.float32) * 2. else: dx = np.array([0.5, 0.5, 2]) * 2. yaw = selected_actor_rotation.yaw/180*np.pi relative_yaw = yaw - ego_yaw relative_rotation = [selected_actor_rotation.roll-ego_rotation.roll, selected_actor_rotation.pitch-ego_rotation.pitch, selected_actor_rotation.yaw-ego_rotation.yaw] relative_rotation = [_/180*np.pi for _ in relative_rotation] relative_pos = np.dot(ego_inv_mat, selected_actor_matrix)[:3, 3].astype(np.float32) selected_actor_transform = selected_actor.get_transform() selected_actor_control = selected_actor_velocity = selected_actor_speed = selected_actor_brake = None if actor_type in ["vehicle", "walker"]: selected_actor_control = selected_actor.get_control() selected_actor_velocity = selected_actor.get_velocity() selected_actor_speed = self._get_forward_speed(transform=selected_actor_transform, velocity=selected_actor_velocity) # In m/s if actor_type == "vehicle": selected_actor_brake = selected_actor_control.brake #vehicle_brake = selected_actor_control.brake # filter bbox that didn't contains points of contains less points num_in_bbox_points = self.get_points_in_bbox(ego_matrix, selected_actor_inv_matrix, dx, lidar) distance = np.linalg.norm(relative_pos).astype(np.float32) result = { "class": actor_type, "extent": [dx[0], dx[1], dx[2],], "relative_position": [relative_pos[0], relative_pos[1], relative_pos[2]], "relative_rotation": relative_rotation, "num_points": int(num_in_bbox_points), "distance": distance, "speed": selected_actor_speed, "brake": selected_actor_brake, "id": int(selected_actor_id), "ego_matrix": selected_actor_matrix.tolist(), "ego_inv_matrix":selected_actor_inv_matrix.tolist(), } results[actor_type+str(selected_actor_id)] = result return results def _find_obstacle_3dbb(self, obstacle_type, max_distance=50): """Returns a list of 3d bounding boxes of type obstacle_type. If the object does have a bounding box, this is returned. Otherwise a bb of size 0.5,0.5,2 is returned at the origin of the object. Args: obstacle_type (String): Regular expression max_distance (int, optional): max search distance. Returns all bbs in this radius. Defaults to 50. Returns: List: List of Boundingboxes """ obst = list() _actors = self._world.get_actors() _obstacles = _actors.filter(obstacle_type) for _obstacle in _obstacles: distance_to_car = _obstacle.get_transform().location.distance(self._ego_vehicle.get_location()) if 0 < distance_to_car <= max_distance: if hasattr(_obstacle, 'bounding_box'): loc = _obstacle.bounding_box.location _obstacle.get_transform().transform(loc) extent = _obstacle.bounding_box.extent _rotation_matrix = self.get_matrix(carla.Transform(carla.Location(0,0,0), _obstacle.get_transform().rotation)) rotated_extent = np.squeeze(np.array((np.array([[extent.x, extent.y, extent.z, 1]]) @ _rotation_matrix)[:3])) bb = np.array([ [loc.x, loc.y, loc.z], [rotated_extent[0], rotated_extent[1], rotated_extent[2]] ]) else: loc = _obstacle.get_transform().location bb = np.array([ [loc.x, loc.y, loc.z], [0.5, 0.5, 2] ]) obst.append(bb) return obst def get_matrix(self, transform): """ Creates matrix from carla transform. """ rotation = transform.rotation location = transform.location c_y = np.cos(np.radians(rotation.yaw)) s_y = np.sin(np.radians(rotation.yaw)) c_r = np.cos(np.radians(rotation.roll)) s_r = np.sin(np.radians(rotation.roll)) c_p = np.cos(np.radians(rotation.pitch)) s_p = np.sin(np.radians(rotation.pitch)) matrix = np.matrix(np.identity(4)) matrix[0, 3] = location.x matrix[1, 3] = location.y matrix[2, 3] = location.z matrix[0, 0] = c_p * c_y matrix[0, 1] = c_y * s_p * s_r - s_y * c_r matrix[0, 2] = -c_y * s_p * c_r - s_y * s_r matrix[1, 0] = s_y * c_p matrix[1, 1] = s_y * s_p * s_r + c_y * c_r matrix[1, 2] = -s_y * s_p * c_r + c_y * s_r matrix[2, 0] = s_p matrix[2, 1] = -c_p * s_r matrix[2, 2] = c_p * c_r return matrix ================================================ FILE: leaderboard/team_code/thinktwice_agent.py ================================================ import os import json import datetime import pathlib from select import select import time from unittest import result import cv2 import carla from collections import deque import math from collections import OrderedDict import pickle import copy import torch import carla import numpy as np from PIL import Image from torchvision import transforms as T from leaderboard.autoagents import autonomous_agent import sys from team_code.planner import RoutePlanner from importlib import import_module SAVE_PATH = os.environ.get('SAVE_PATH', None) import cv2 import mmcv from mmcv import Config from mmdet3d.models import build_model from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model) from mmdet3d.datasets.pipelines import Compose from mmdet3d.core.points import get_points_type import open_loop_training.code.datasets.carla_dataset as ds_module from mmcv.parallel.collate import collate as mm_collate_to_batch_form def get_entry_point(): return 'ThinkTwiceAgent' class GlobalConfig: def __init__(self, init_dic): for k, v in init_dic.items(): setattr(self, k, v) def obtain_transform_matrix(x, y, yaw): cy = math.cos(yaw) sy = math.sin(yaw) cr = 1 sr = 0 cp = 1 sp = 0 mat = np.array([ [cp * cy, cy * sp * sr - sy * cr, -cy * sp * cr - sy * sr, x,], [cp * sy, sy * sp * sr + cy * cr, -sy * sp * cr + cy * sr, y], [sp, -cp * sr, cp * cr, 0], [0.0, 0.0, 0.0, 1.0], ]) return mat def InverseRotateVector(x, y, yaw): z = 0 cy = math.cos(yaw) sy = math.sin(yaw) cr = 1 sr = 0 cp = 1 sp = 0 out_x = x * (cp * cy) + y * (cp * sy) + z * (sp) out_y = x * (cy * sp * sr - sy * cr) + y * (sy * sp * sr + cy * cr) + z * (-cp * sr) return out_x, out_y def obtain_inv_transform_matrix(x, y, yaw): x = -x y = -y x, y = InverseRotateVector(x, y, yaw) cy = math.cos(yaw) sy = math.sin(yaw) cr = 1 sr = 0 cp = 1 sp = 0 inv_mat = np.array([ [cp * cy, cp * sy, sp, x,], [cy * sp * sr - sy * cr, sy * sp * sr + cy * cr, -cp * sr, y,], [-cy * sp * cr - sy * sr, -sy * sp * cr + cy * sr, cp * cr, 0,], [0., 0., 0., 1.0], ]) return inv_mat # Taken from World on Rails class EgoModel(): def __init__(self, dt=1./4): self.dt = dt # Kinematic bicycle model. Numbers are the tuned parameters from World on Rails self.front_wb = -0.090769015 self.rear_wb = 1.4178275 self.steer_gain = 0.36848336 self.brake_accel = -4.952399 self.throt_accel = 0.5633837 def forward(self, locs, yaws, spds, acts): # Kinematic bicycle model. Numbers are the tuned parameters from World on Rails steer = acts[..., 0:1].item() throt = acts[..., 1:2].item() brake = acts[..., 2:3].astype(np.uint8) if (brake): accel = self.brake_accel else: accel = self.throt_accel * throt wheel = self.steer_gain * steer beta = math.atan(self.rear_wb / (self.front_wb + self.rear_wb) * math.tan(wheel)) yaws = yaws.item() spds = spds.item() next_locs_0 = locs[0].item() + spds * math.cos(yaws + beta) * self.dt next_locs_1 = locs[1].item() + spds * math.sin(yaws + beta) * self.dt next_yaws = yaws + spds / self.rear_wb * math.sin(beta) * self.dt next_spds = spds + accel * self.dt next_spds = next_spds * (next_spds > 0.0) # Fast ReLU next_locs = np.array([next_locs_0, next_locs_1]) next_yaws = np.array(next_yaws) next_spds = np.array(next_spds) return next_locs, next_yaws, next_spds class ThinkTwiceAgent(autonomous_agent.AutonomousAgent): def setup(self, path_to_conf_file): self.device = "cuda:0" self.track = autonomous_agent.Track.SENSORS ### For temporal information self.data_queue = deque() self.data_queue_len = 31 ### Under 20 Hz self.pred_len = 4 self.points_class = get_points_type('LIDAR') self.config_path = path_to_conf_file self.step = -1 self.wall_start = time.time() self.initialized = False path_to_conf_file = path_to_conf_file.split("+") ckpt_path = path_to_conf_file[0] config_path = path_to_conf_file[1] cfg = Config.fromfile(config_path) ## For mmcv if hasattr(cfg, 'plugin'): if cfg.plugin: import importlib if hasattr(cfg, 'plugin_dir'): plugin_dir = cfg.plugin_dir plugin_dir = os.path.join("open_loop_training", plugin_dir) _module_dir = os.path.dirname(plugin_dir) _module_dir = _module_dir.split('/') _module_path = _module_dir[0] for m in _module_dir[1:]: _module_path = _module_path + '.' + m print(_module_path) plg_lib = importlib.import_module(_module_path) self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg')) print(ckpt_path) checkpoint = load_checkpoint(self.model, ckpt_path, map_location='cpu') self.model = self.model.to(self.device) self.model.eval() ## For mmcv to preprocess single frames self.test_pipeline = [] cfg.val_full_queue_pipeline[0].cfg.use_depth = False ##No gt for testing cfg.val_full_queue_pipeline[0].cfg.use_seg = False ##No gt for testing for test_pipeline in cfg.test_pipeline: if test_pipeline["type"] not in ["LoadMultiImages", "LoadPoints", 'LoadDepth', 'LoadSeg']: self.test_pipeline .append(test_pipeline) self.test_pipeline = Compose(self.test_pipeline) ## For mmcv to preprocess temporal information self.seq_test_pipeline = Compose(cfg.val_full_queue_pipeline) self.save_path = None if SAVE_PATH is not None: now = datetime.datetime.now() string = pathlib.Path(os.environ['ROUTES']).stem + '_' string += '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second))) if len(path_to_conf_file) > 2: string += "_index" + str(path_to_conf_file[2]) + "_" + str(path_to_conf_file[3]) self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string self.save_path.mkdir(parents=True, exist_ok=False) (self.save_path / 'meta').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_front').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_left').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_right').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_back').mkdir(parents=True, exist_ok=True) (self.save_path / 'topdown').mkdir(parents=True, exist_ok=True) (self.save_path / 'lidar').mkdir(parents=True, exist_ok=True) self.cfg = cfg self.folder_name = string ## Creep self.stuck_detector = 0 self.stuck_threshold = 20.0 topdown_extrinsics = np.array([[0.0, -0.0, -1.0, 50.0], [0.0, 1.0, -0.0, 0.0], [1.0, -0.0, 0.0, -0.0], [0.0, 0.0, 0.0, 1.0]]) unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]]) self.coor2topdown = unreal2cam @ topdown_extrinsics topdown_intrinsics = np.array([[548.993771650447, 0.0, 256.0, 0], [0.0, 548.993771650447, 256.0, 0], [0.0, 0.0, 1.0, 0], [0, 0, 0, 1.0]]) self.coor2topdown = topdown_intrinsics @ self.coor2topdown self.ego_model = EgoModel(dt=1.0 / 20.0) self.gps_buffer = deque(maxlen=100) def _init(self): self._route_planner = RoutePlanner(4.0, 50.0) self._route_planner.set_route(self._global_plan, True) self.prev_lidar = None self.prev_matrix = None self.initialized = True def _get_position(self, tick_data): gps = tick_data['gps'] gps = (gps - self._route_planner.mean) * self._route_planner.scale return gps def sensors(self): return [ { 'type': 'sensor.camera.rgb', 'x': 1.5, 'y': 0.0, 'z':2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_front' }, { 'type': 'sensor.camera.rgb', 'x': 0, 'y': -0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_left' }, { 'type': 'sensor.camera.rgb', 'x': 0, 'y': 0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_right' }, { 'type': 'sensor.camera.rgb', 'x': -1.6, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_back' }, { 'type': 'sensor.lidar.ray_cast', 'x': 0.0, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'id': 'lidar' }, { 'type': 'sensor.other.imu', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.05, 'id': 'imu' }, { 'type': 'sensor.other.gnss', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.01, 'id': 'gps' }, { 'type': 'sensor.speedometer', 'reading_frequency': 20, 'id': 'speed' }, ### Debug sensor, not used by the model { 'type': 'sensor.camera.rgb', 'x': 0.0, 'y': 0.0, 'z': 50.0, 'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0, 'width': 512, 'height': 512, 'fov': 5 * 10.0, 'id': 'topdown' }, ] def tick(self, input_data): self.step += 1 topdown = cv2.cvtColor(input_data['topdown'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_front = cv2.cvtColor(input_data['rgb_front'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_left = cv2.cvtColor(input_data['rgb_left'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_right = cv2.cvtColor(input_data['rgb_right'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_back = cv2.cvtColor(input_data['rgb_back'][1][:, :, :3], cv2.COLOR_BGR2RGB) gps = input_data['gps'][1][:2] speed = input_data['speed'][1]['speed'] compass = input_data['imu'][1][-1] acceleration = input_data['imu'][1][:3] angular_velocity = input_data['imu'][1][3:6] if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames compass = 0.0 acceleration = np.zeros(3) angular_velocity = np.zeros(3) result = { 'rgb_front': rgb_front, 'rgb_left': rgb_left, 'rgb_right': rgb_right, 'rgb_back': rgb_back, 'gps': gps, 'speed': speed, 'theta': compass, "acceleration":acceleration, "angular_velocity":angular_velocity, "topdown": topdown, "acceleration":acceleration.tolist(), "angular_velocity":angular_velocity.tolist() } pos = self._get_position(result) self.gps_buffer.append(pos) pos = np.average(self.gps_buffer, axis=0) result["x"] = pos[0] result["y"] = pos[1] result['gps'] = pos next_wp, next_cmd = self._route_planner.run_step(pos) result['next_command'] = next_cmd.value result['x_target'] = next_wp[0] result['y_target'] = next_wp[1] ## Lidar is 10Hz and the simulator is running 20Hz -> Each frame the Lidar only returns 180 degree point clouds now_lidar = input_data['lidar'][1] if self.prev_lidar is not None: now_inv_mat = obtain_inv_transform_matrix(pos[1], -pos[0], compass-np.pi/2) relative_transform_mat = np.dot(now_inv_mat , np.array(self.prev_matrix)) #4 * 4 transformed_prev_lidar_xyz = np.concatenate([self.prev_lidar[:, :3], np.ones((self.prev_lidar.shape[0], 1))], axis=1) # N * 4 transformed_prev_lidar_xyz = np.einsum("ij,kj->ki", relative_transform_mat, transformed_prev_lidar_xyz) transformed_prev_lidar_xyz = np.concatenate([transformed_prev_lidar_xyz[:, :3], self.prev_lidar[:, 3][:, np.newaxis]], axis=1) saved_lidar = np.concatenate([transformed_prev_lidar_xyz, now_lidar], axis=0).copy() saved_lidar[:, 2] += 2.5 else: saved_lidar = now_lidar.copy() saved_lidar[:, 2] += 2.5 result["lidar"] = saved_lidar.astype(np.float32) self.prev_lidar = now_lidar self.prev_matrix = obtain_transform_matrix(pos[1], -pos[0], compass-np.pi/2) return result def offset_then_rotate(self, target_2d_world_coor, ref_2d_wolrd_coor, ref_yaw): final_coor = target_2d_world_coor - ref_2d_wolrd_coor R = np.array([ [np.cos(ref_yaw), -np.sin(ref_yaw)], [np.sin(ref_yaw), np.cos(ref_yaw)] ]) return np.einsum("ij,kj->ki", R.T, final_coor) @torch.no_grad() def run_step(self, input_data, timestamp): if not self.initialized: self._init() tick_data = self.tick(input_data) ################# Preprocess ################ results = {} ego_theta = tick_data["theta"] if not np.isnan(tick_data["theta"]) else 0 ego_theta = ego_theta - np.pi/2 results["input_theta"] = ego_theta results["input_x"] = tick_data["y"] results["input_y"] = -tick_data["x"] ego_xy = np.stack([results["input_x"], results["input_y"]], axis=-1) results["speed"] = tick_data["speed"] results["can_bus"] = np.zeros(18) results["can_bus"][0] = results["input_x"] #Gloabal results["can_bus"][1] = results["input_y"] #Global accel = np.array(tick_data["acceleration"]) accel[:2] = self.offset_then_rotate(np.array(accel[:2])[np.newaxis, :], np.array([0, 0]), ego_theta).squeeze(0) results["can_bus"][7:10] = accel results["can_bus"][10:13] = tick_data["angular_velocity"] results["can_bus"][13] = tick_data["speed"] results["can_bus"][-2] = ego_theta results["can_bus"][-1] = ego_theta / np.pi * 180 results['target_point'] = self.offset_then_rotate(np.array([[tick_data["y_target"], -tick_data["x_target"]]]), ego_xy, ego_theta).squeeze(0) command = tick_data['next_command'] if command < 0: command = 4 command -= 1 results['target_command_raw'] = torch.tensor(command).long() assert command in [0, 1, 2, 3, 4, 5] cmd_one_hot = [0] * 6 cmd_one_hot[command] = 1 results['target_command'] = torch.tensor(cmd_one_hot) ## Inference mode, all empty results['waypoints'] = np.zeros(4) results["action"] = np.zeros(3) results["action_mu"] = np.zeros(2) results["action_sigma"] = np.zeros(2) results['future_action_mu'] = np.zeros((self.pred_len, 2)) results['future_action_sigma'] = np.zeros((self.pred_len, 2)) results['future_action'] = np.zeros((self.pred_len, 3)) results["value"] = 0 results["feature"] = np.zeros(1) results["future_feature"] = np.zeros((self.pred_len, 1)) results["img"] = [tick_data[camera_name] for camera_name in self.cfg["camera_list"]] points = tick_data["lidar"] points = self.points_class( points, points_dim=points.shape[-1], attribute_dims=None) results["points"] = points results = self.test_pipeline(results) if len(self.data_queue) >= self.data_queue_len: self.data_queue.popleft() self.data_queue.append(results) if self.step < self.data_queue_len: control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 self.update_gps_buffer(control, tick_data['theta'], tick_data['speed']) return control ## Preprocess selected_index_lis = [] for selected_index in self.cfg["cfg"]["history_query_index_lis"][:-1]: selected_index = selected_index * 10 ## train in 2Hz while Simulator is in 20 Hz selected_index_lis.append(selected_index-1) selected_index_lis.append(-1) input_data_queue = [copy.deepcopy(self.data_queue[selected_index]) for selected_index in selected_index_lis] input_data_union = ds_module.union2one(self.seq_test_pipeline, input_data_queue) input_data_batch = mm_collate_to_batch_form([input_data_union], samples_per_gpu=1) input_data_batch["img"] = input_data_batch["img"].data[0] if len(selected_index_lis) == 1: input_data_batch["img"] = input_data_batch["img"].squeeze(0) input_data_batch["points"] = input_data_batch["points"].data[0] input_data_batch["img_metas"] = input_data_batch["img_metas"].data[0] for _ in input_data_batch: if torch.is_tensor(input_data_batch[_]): input_data_batch[_] = input_data_batch[_].to(self.device) with torch.no_grad(): pred = self.model.forward_inference(input_data_batch) gt_velocity = torch.FloatTensor([tick_data['speed']]).to(self.device, dtype=torch.float32) steer_ctrl, throttle_ctrl, brake_ctrl, metadata = self.model.process_action(pred, tick_data['next_command'], gt_velocity, results['target_point']) steer_traj, throttle_traj, brake_traj, metadata_traj = self.model.control_pid(pred['pred_wp'][:, -1, :, :], gt_velocity, results['target_point']) if brake_traj < 0.05: brake_traj = 0.0 if throttle_traj > brake_traj: brake_traj = 0.0 overall_pred_is_accel = ((throttle_traj>0) or (throttle_ctrl>0) or (brake_traj<0.95) or (brake_ctrl<0.95)) overall_pred_is_brake = ((brake_traj>0.2) or (brake_ctrl>0.2)) control = carla.VehicleControl() control.steer = steer_ctrl is_turn = False if abs(control.steer) > 0.07: ## In turning is_turn = True speed_threshold = 1.5 ## Reduce stuck during turning else: speed_threshold = 3.5 ## Recude red light infraction/collision if overall_pred_is_brake: control.brake=1.0 control.throttle=0.0 else: control.brake=0.0 control.throttle=1.0 is_stuck = False # By transfuser, crawl if(self.stuck_detector > self.stuck_threshold): print("Detected agent being stuck.", "Frame:", self.step // 10) is_stuck = True if overall_pred_is_accel: control.brake = 0.0 control.throttle = 1.0 else: control.brake = 1.0 control.throttle = 0.0 if(float(gt_velocity) < 0.5): # just an arbitrary low number to threshhold when the car is stopped self.stuck_detector += 1 elif(float(gt_velocity) > 0.5): self.stuck_detector = 0 if float(tick_data['speed']) > speed_threshold: max_throttle = 0.05 else: if is_turn: max_throttle = 0.4 else: max_throttle = 0.6 control.throttle = np.clip(control.throttle, a_min=0.0, a_max=max_throttle) self.pid_metadata = {} self.pid_metadata['steer_ctrl'] = float(steer_ctrl) self.pid_metadata['steer_traj'] = float(steer_traj) self.pid_metadata['throttle_ctrl'] = float(throttle_ctrl) self.pid_metadata['throttle_traj'] = float(throttle_traj) self.pid_metadata['brake_ctrl'] = float(brake_ctrl) self.pid_metadata['brake_traj'] = float(brake_traj) self.pid_metadata["is_stuck"] = is_stuck self.pid_metadata["stuck_detector"] = self.stuck_detector self.pid_metadata['steer'] = control.steer self.pid_metadata["brake"] = control.brake self.pid_metadata["throttle"] = control.throttle self.pid_metadata["speed"] = float(tick_data['speed']) if SAVE_PATH is not None and self.step % 10 == 0: self.save(tick_data) self.update_gps_buffer(control, tick_data['theta'], tick_data['speed']) return control def save(self, tick_data): frame = self.step // 10 Image.fromarray(tick_data['rgb_front']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame)) #Image.fromarray(tick_data['rgb_left']).save(self.save_path / 'rgb_left' / ('%04d.png' % frame)) #Image.fromarray(tick_data['rgb_right']).save(self.save_path / 'rgb_right' / ('%04d.png' % frame)) #Image.fromarray(tick_data['rgb_back']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame)) Image.fromarray(tick_data['topdown']).save(self.save_path / 'topdown' / ('%04d.png' % frame)) outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w') json.dump(self.pid_metadata, outfile, indent=4) outfile.close() #np.save(self.save_path / 'lidar' / ('%04d.npy' % frame), tick_data["lidar"].astype(np.float32), allow_pickle=True) def destroy(self): del self.model torch.cuda.empty_cache() def update_gps_buffer(self, control, theta, speed): yaw = np.array([(theta - np.pi/2.0)]) speed = np.array([speed]) action = np.array(np.stack([control.steer, control.throttle, control.brake], axis=-1)) #Update gps locations for i in range(len(self.gps_buffer)): loc =self.gps_buffer[i] loc_temp = np.array([loc[1], -loc[0]]) #Bicycle model uses a different coordinate system next_loc_tmp, _, _ = self.ego_model.forward(loc_temp, yaw, speed, action) next_loc = np.array([-next_loc_tmp[1], next_loc_tmp[0]]) self.gps_buffer[i] = next_loc return None ================================================ FILE: leaderboard/team_code/thinktwice_agent_old.py ================================================ import os import json import datetime import pathlib from select import select import time from unittest import result import cv2 import carla from collections import deque import math from collections import OrderedDict import pickle import copy import torch import carla import numpy as np from PIL import Image from torchvision import transforms as T from leaderboard.autoagents import autonomous_agent import sys from team_code.planner import RoutePlanner from importlib import import_module SAVE_PATH = os.environ.get('SAVE_PATH', None) import cv2 import mmcv from mmcv import Config from mmdet3d.models import build_model from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model) from mmdet3d.datasets.pipelines import Compose from mmdet3d.core.points import get_points_type import open_loop_training.code.datasets.carla_dataset as ds_module from mmcv.parallel.collate import collate as mm_collate_to_batch_form def get_entry_point(): return 'ThinkTwiceAgent' class GlobalConfig: def __init__(self, init_dic): for k, v in init_dic.items(): setattr(self, k, v) def obtain_transform_matrix(x, y, yaw): cy = math.cos(yaw) sy = math.sin(yaw) cr = 1 sr = 0 cp = 1 sp = 0 mat = np.array([ [cp * cy, cy * sp * sr - sy * cr, -cy * sp * cr - sy * sr, x,], [cp * sy, sy * sp * sr + cy * cr, -sy * sp * cr + cy * sr, y], [sp, -cp * sr, cp * cr, 0], [0.0, 0.0, 0.0, 1.0], ]) return mat def InverseRotateVector(x, y, yaw): z = 0 cy = math.cos(yaw) sy = math.sin(yaw) cr = 1 sr = 0 cp = 1 sp = 0 out_x = x * (cp * cy) + y * (cp * sy) + z * (sp) out_y = x * (cy * sp * sr - sy * cr) + y * (sy * sp * sr + cy * cr) + z * (-cp * sr) return out_x, out_y def obtain_inv_transform_matrix(x, y, yaw): x = -x y = -y x, y = InverseRotateVector(x, y, yaw) cy = math.cos(yaw) sy = math.sin(yaw) cr = 1 sr = 0 cp = 1 sp = 0 inv_mat = np.array([ [cp * cy, cp * sy, sp, x,], [cy * sp * sr - sy * cr, sy * sp * sr + cy * cr, -cp * sr, y,], [-cy * sp * cr - sy * sr, -sy * sp * cr + cy * sr, cp * cr, 0,], [0., 0., 0., 1.0], ]) return inv_mat # Taken from World on Rails class EgoModel(): def __init__(self, dt=1./4): self.dt = dt # Kinematic bicycle model. Numbers are the tuned parameters from World on Rails self.front_wb = -0.090769015 self.rear_wb = 1.4178275 self.steer_gain = 0.36848336 self.brake_accel = -4.952399 self.throt_accel = 0.5633837 def forward(self, locs, yaws, spds, acts): # Kinematic bicycle model. Numbers are the tuned parameters from World on Rails steer = acts[..., 0:1].item() throt = acts[..., 1:2].item() brake = acts[..., 2:3].astype(np.uint8) if (brake): accel = self.brake_accel else: accel = self.throt_accel * throt wheel = self.steer_gain * steer beta = math.atan(self.rear_wb / (self.front_wb + self.rear_wb) * math.tan(wheel)) yaws = yaws.item() spds = spds.item() next_locs_0 = locs[0].item() + spds * math.cos(yaws + beta) * self.dt next_locs_1 = locs[1].item() + spds * math.sin(yaws + beta) * self.dt next_yaws = yaws + spds / self.rear_wb * math.sin(beta) * self.dt next_spds = spds + accel * self.dt next_spds = next_spds * (next_spds > 0.0) # Fast ReLU next_locs = np.array([next_locs_0, next_locs_1]) next_yaws = np.array(next_yaws) next_spds = np.array(next_spds) return next_locs, next_yaws, next_spds class ThinkTwiceAgent(autonomous_agent.AutonomousAgent): def setup(self, path_to_conf_file): self.device = "cuda:0" self.track = autonomous_agent.Track.SENSORS ### For temporal information self.data_queue = deque() self.data_queue_len = 31 ### Under 20 Hz self.pred_len = 4 self.points_class = get_points_type('LIDAR') self.config_path = path_to_conf_file self.step = -1 self.wall_start = time.time() self.initialized = False path_to_conf_file = path_to_conf_file.split("+") ckpt_path = path_to_conf_file[0] config_path = path_to_conf_file[1] cfg = Config.fromfile(config_path) ## For mmcv if hasattr(cfg, 'plugin'): if cfg.plugin: import importlib if hasattr(cfg, 'plugin_dir'): plugin_dir = cfg.plugin_dir plugin_dir = os.path.join("open_loop_training", plugin_dir) _module_dir = os.path.dirname(plugin_dir) _module_dir = _module_dir.split('/') _module_path = _module_dir[0] for m in _module_dir[1:]: _module_path = _module_path + '.' + m print(_module_path) plg_lib = importlib.import_module(_module_path) self.model = build_model(cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg')) print(ckpt_path) checkpoint = load_checkpoint(self.model, ckpt_path, map_location='cpu') self.model = self.model.to(self.device) self.model.eval() ## For mmcv to preprocess single frames self.test_pipeline = [] cfg.val_full_queue_pipeline[0].cfg.use_depth = False ##No gt for testing cfg.val_full_queue_pipeline[0].cfg.use_seg = False ##No gt for testing for test_pipeline in cfg.test_pipeline: if test_pipeline["type"] not in ["LoadMultiImages", "LoadPoints", 'LoadDepth', 'LoadSeg']: self.test_pipeline .append(test_pipeline) self.test_pipeline = Compose(self.test_pipeline) ## For mmcv to preprocess temporal information self.seq_test_pipeline = Compose(cfg.val_full_queue_pipeline) self.save_path = None if SAVE_PATH is not None: now = datetime.datetime.now() string = pathlib.Path(os.environ['ROUTES']).stem + '_' string += '_'.join(map(lambda x: '%02d' % x, (now.month, now.day, now.hour, now.minute, now.second))) if len(path_to_conf_file) > 2: string += "_index" + str(path_to_conf_file[2]) + "_" + str(path_to_conf_file[3]) self.save_path = pathlib.Path(os.environ['SAVE_PATH']) / string self.save_path.mkdir(parents=True, exist_ok=False) (self.save_path / 'meta').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_front').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_left').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_right').mkdir(parents=True, exist_ok=True) (self.save_path / 'rgb_back').mkdir(parents=True, exist_ok=True) (self.save_path / 'topdown').mkdir(parents=True, exist_ok=True) (self.save_path / 'lidar').mkdir(parents=True, exist_ok=True) self.cfg = cfg self.folder_name = string ## Creep self.stuck_detector = 0 self.stuck_threshold = 20.0 topdown_extrinsics = np.array([[0.0, -0.0, -1.0, 50.0], [0.0, 1.0, -0.0, 0.0], [1.0, -0.0, 0.0, -0.0], [0.0, 0.0, 0.0, 1.0]]) unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]]) self.coor2topdown = unreal2cam @ topdown_extrinsics topdown_intrinsics = np.array([[548.993771650447, 0.0, 256.0, 0], [0.0, 548.993771650447, 256.0, 0], [0.0, 0.0, 1.0, 0], [0, 0, 0, 1.0]]) self.coor2topdown = topdown_intrinsics @ self.coor2topdown self.ego_model = EgoModel(dt=1.0 / 20.0) self.gps_buffer = deque(maxlen=100) def _init(self): self._route_planner = RoutePlanner(4.0, 50.0) self._route_planner.set_route(self._global_plan, True) self.prev_lidar = None self.prev_matrix = None self.initialized = True def _get_position(self, tick_data): gps = tick_data['gps'] gps = (gps - self._route_planner.mean) * self._route_planner.scale return gps def sensors(self): return [ { 'type': 'sensor.camera.rgb', 'x': 1.5, 'y': 0.0, 'z':2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_front' }, { 'type': 'sensor.camera.rgb', 'x': 0, 'y': -0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': -90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_left' }, { 'type': 'sensor.camera.rgb', 'x': 0, 'y': 0.3, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 90.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_right' }, { 'type': 'sensor.camera.rgb', 'x': -1.6, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, 'width': 1600, 'height': 900, 'fov': 150, 'id': 'rgb_back' }, { 'type': 'sensor.lidar.ray_cast', 'x': 0.0, 'y': 0.0, 'z': 2.5, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'id': 'lidar' }, { 'type': 'sensor.other.imu', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.05, 'id': 'imu' }, { 'type': 'sensor.other.gnss', 'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'sensor_tick': 0.01, 'id': 'gps' }, { 'type': 'sensor.speedometer', 'reading_frequency': 20, 'id': 'speed' }, ### Debug sensor, not used by the model { 'type': 'sensor.camera.rgb', 'x': 0.0, 'y': 0.0, 'z': 50.0, 'roll': 0.0, 'pitch': -90.0, 'yaw': 0.0, 'width': 512, 'height': 512, 'fov': 5 * 10.0, 'id': 'topdown' }, ] def tick(self, input_data): self.step += 1 topdown = cv2.cvtColor(input_data['topdown'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_front = cv2.cvtColor(input_data['rgb_front'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_left = cv2.cvtColor(input_data['rgb_left'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_right = cv2.cvtColor(input_data['rgb_right'][1][:, :, :3], cv2.COLOR_BGR2RGB) rgb_back = cv2.cvtColor(input_data['rgb_back'][1][:, :, :3], cv2.COLOR_BGR2RGB) gps = input_data['gps'][1][:2] speed = input_data['speed'][1]['speed'] compass = input_data['imu'][1][-1] acceleration = input_data['imu'][1][:3] angular_velocity = input_data['imu'][1][3:6] if (math.isnan(compass) == True): #It can happen that the compass sends nan for a few frames compass = 0.0 acceleration = np.zeros(3) angular_velocity = np.zeros(3) result = { 'rgb_front': rgb_front, 'rgb_left': rgb_left, 'rgb_right': rgb_right, 'rgb_back': rgb_back, 'gps': gps, 'speed': speed, 'theta': compass, "acceleration":acceleration, "angular_velocity":angular_velocity, "topdown": topdown, "acceleration":acceleration.tolist(), "angular_velocity":angular_velocity.tolist() } pos = self._get_position(result) self.gps_buffer.append(pos) pos = np.average(self.gps_buffer, axis=0) result["x"] = pos[0] result["y"] = pos[1] result['gps'] = pos next_wp, next_cmd = self._route_planner.run_step(pos) result['next_command'] = next_cmd.value result['x_target'] = next_wp[0] result['y_target'] = next_wp[1] ## Lidar is 10Hz and the simulator is running 20Hz -> Each frame the Lidar only returns 180 degree point clouds now_lidar = input_data['lidar'][1] if self.prev_lidar is not None: now_inv_mat = obtain_inv_transform_matrix(pos[1], -pos[0], compass-np.pi/2) relative_transform_mat = np.dot(now_inv_mat , np.array(self.prev_matrix)) #4 * 4 transformed_prev_lidar_xyz = np.concatenate([self.prev_lidar[:, :3], np.ones((self.prev_lidar.shape[0], 1))], axis=1) # N * 4 transformed_prev_lidar_xyz = np.einsum("ij,kj->ki", relative_transform_mat, transformed_prev_lidar_xyz) transformed_prev_lidar_xyz = np.concatenate([transformed_prev_lidar_xyz[:, :3], self.prev_lidar[:, 3][:, np.newaxis]], axis=1) saved_lidar = np.concatenate([transformed_prev_lidar_xyz, now_lidar], axis=0).copy() saved_lidar[:, 2] += 2.5 else: saved_lidar = now_lidar.copy() saved_lidar[:, 2] += 2.5 result["lidar"] = saved_lidar.astype(np.float32) self.prev_lidar = now_lidar self.prev_matrix = obtain_transform_matrix(pos[1], -pos[0], compass-np.pi/2) return result def offset_then_rotate(self, target_2d_world_coor, ref_2d_wolrd_coor, ref_yaw): final_coor = target_2d_world_coor - ref_2d_wolrd_coor R = np.array([ [np.cos(ref_yaw), -np.sin(ref_yaw)], [np.sin(ref_yaw), np.cos(ref_yaw)] ]) return np.einsum("ij,kj->ki", R.T, final_coor) @torch.no_grad() def run_step(self, input_data, timestamp): if not self.initialized: self._init() tick_data = self.tick(input_data) ################# Preprocess ################ results = {} ego_theta = tick_data["theta"] if not np.isnan(tick_data["theta"]) else 0 ego_theta = ego_theta - np.pi/2 results["input_theta"] = ego_theta results["input_x"] = tick_data["y"] results["input_y"] = -tick_data["x"] ego_xy = np.stack([results["input_x"], results["input_y"]], axis=-1) results["speed"] = tick_data["speed"] results["can_bus"] = np.zeros(18) results["can_bus"][0] = results["input_x"] #Gloabal results["can_bus"][1] = results["input_y"] #Global accel = np.array(tick_data["acceleration"]) accel[:2] = self.offset_then_rotate(np.array(accel[:2])[np.newaxis, :], np.array([0, 0]), ego_theta).squeeze(0) results["can_bus"][7:10] = accel results["can_bus"][10:13] = tick_data["angular_velocity"] results["can_bus"][13] = tick_data["speed"] results["can_bus"][-2] = ego_theta results["can_bus"][-1] = ego_theta / np.pi * 180 results['target_point'] = self.offset_then_rotate(np.array([[tick_data["y_target"], -tick_data["x_target"]]]), ego_xy, ego_theta).squeeze(0) command = tick_data['next_command'] if command < 0: command = 4 command -= 1 results['target_command_raw'] = torch.tensor(command).long() assert command in [0, 1, 2, 3, 4, 5] cmd_one_hot = [0] * 6 cmd_one_hot[command] = 1 results['target_command'] = torch.tensor(cmd_one_hot) ## Inference mode, all empty results['waypoints'] = np.zeros(4) results["action"] = np.zeros(3) results["action_mu"] = np.zeros(2) results["action_sigma"] = np.zeros(2) results['future_action_mu'] = np.zeros((self.pred_len, 2)) results['future_action_sigma'] = np.zeros((self.pred_len, 2)) results['future_action'] = np.zeros((self.pred_len, 3)) results["value"] = 0 results["feature"] = np.zeros(1) results["future_feature"] = np.zeros((self.pred_len, 1)) results["img"] = [tick_data[camera_name] for camera_name in self.cfg["camera_list"]] points = tick_data["lidar"] points = self.points_class( points, points_dim=points.shape[-1], attribute_dims=None) results["points"] = points results = self.test_pipeline(results) if len(self.data_queue) >= self.data_queue_len: self.data_queue.popleft() self.data_queue.append(results) if self.step < self.data_queue_len: control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 self.update_gps_buffer(control, tick_data['theta'], tick_data['speed']) return control ## Preprocess selected_index_lis = [] for selected_index in self.cfg["cfg"]["history_query_index_lis"][:-1]: selected_index = selected_index * 10 ## train in 2Hz while Simulator is in 20 Hz selected_index_lis.append(selected_index-1) selected_index_lis.append(-1) input_data_queue = [copy.deepcopy(self.data_queue[selected_index]) for selected_index in selected_index_lis] input_data_union = ds_module.union2one(self.seq_test_pipeline, input_data_queue) input_data_batch = mm_collate_to_batch_form([input_data_union], samples_per_gpu=1) input_data_batch["img"] = input_data_batch["img"].data[0] if len(selected_index_lis) == 1: input_data_batch["img"] = input_data_batch["img"].squeeze(0) input_data_batch["points"] = input_data_batch["points"].data[0] input_data_batch["img_metas"] = input_data_batch["img_metas"].data[0] for _ in input_data_batch: if torch.is_tensor(input_data_batch[_]): input_data_batch[_] = input_data_batch[_].to(self.device) with torch.no_grad(): pred = self.model.forward_inference(input_data_batch) gt_velocity = torch.FloatTensor([tick_data['speed']]).to(self.device, dtype=torch.float32) steer_ctrl, throttle_ctrl, brake_ctrl, metadata = self.model.process_action(pred, tick_data['next_command'], gt_velocity, results['target_point']) steer_traj, throttle_traj, brake_traj, metadata_traj = self.model.control_pid(pred['pred_wp'][:, -1, :, :], gt_velocity, results['target_point']) if brake_traj < 0.05: brake_traj = 0.0 if throttle_traj > brake_traj: brake_traj = 0.0 overall_pred_is_accel = ((throttle_traj>0) or (throttle_ctrl>0) or (brake_traj<0.3) or (brake_ctrl<0.3)) overall_pred_is_brake = ((brake_traj>0.1) or (brake_ctrl>0.1)) control = carla.VehicleControl() control.steer = steer_ctrl is_turn = False if abs(control.steer) > 0.07: ## In turning is_turn = True speed_threshold = 2.5 ## Reduce stuck during turning else: speed_threshold = 3.0 ## Recude red light infraction/collision if overall_pred_is_brake: control.brake=1.0 control.throttle=0.0 else: control.brake=0.0 control.throttle=0.75 is_stuck = False # By transfuser, crawl if(self.stuck_detector > self.stuck_threshold): print("Detected agent being stuck.", "Frame:", self.step // 10) is_stuck = True if overall_pred_is_accel: control.brake = 0.0 control.throttle = 0.75 else: control.brake = 1.0 control.throttle = 0.0 if(float(gt_velocity) < 0.5): # just an arbitrary low number to threshhold when the car is stopped self.stuck_detector += 1 elif(float(gt_velocity) > 0.5): self.stuck_detector = 0 if float(tick_data['speed']) > speed_threshold: max_throttle = 0.05 else: max_throttle = 0.75 control.throttle = np.clip(control.throttle, a_min=0.0, a_max=max_throttle) self.pid_metadata = {} self.pid_metadata['steer_ctrl'] = float(steer_ctrl) self.pid_metadata['steer_traj'] = float(steer_traj) self.pid_metadata['throttle_ctrl'] = float(throttle_ctrl) self.pid_metadata['throttle_traj'] = float(throttle_traj) self.pid_metadata['brake_ctrl'] = float(brake_ctrl) self.pid_metadata['brake_traj'] = float(brake_traj) self.pid_metadata["is_stuck"] = is_stuck self.pid_metadata["stuck_detector"] = self.stuck_detector self.pid_metadata['steer'] = control.steer self.pid_metadata["brake"] = control.brake self.pid_metadata["throttle"] = control.throttle self.pid_metadata["speed"] = float(tick_data['speed']) if SAVE_PATH is not None and self.step % 10 == 0: self.save(tick_data) self.update_gps_buffer(control, tick_data['theta'], tick_data['speed']) return control def save(self, tick_data): frame = self.step // 10 Image.fromarray(tick_data['rgb_front']).save(self.save_path / 'rgb_front' / ('%04d.png' % frame)) #Image.fromarray(tick_data['rgb_left']).save(self.save_path / 'rgb_left' / ('%04d.png' % frame)) #Image.fromarray(tick_data['rgb_right']).save(self.save_path / 'rgb_right' / ('%04d.png' % frame)) #Image.fromarray(tick_data['rgb_back']).save(self.save_path / 'rgb_back' / ('%04d.png' % frame)) Image.fromarray(tick_data['topdown']).save(self.save_path / 'topdown' / ('%04d.png' % frame)) outfile = open(self.save_path / 'meta' / ('%04d.json' % frame), 'w') json.dump(self.pid_metadata, outfile, indent=4) outfile.close() #np.save(self.save_path / 'lidar' / ('%04d.npy' % frame), tick_data["lidar"].astype(np.float32), allow_pickle=True) def destroy(self): del self.model torch.cuda.empty_cache() def update_gps_buffer(self, control, theta, speed): yaw = np.array([(theta - np.pi/2.0)]) speed = np.array([speed]) action = np.array(np.stack([control.steer, control.throttle, control.brake], axis=-1)) #Update gps locations for i in range(len(self.gps_buffer)): loc =self.gps_buffer[i] loc_temp = np.array([loc[1], -loc[0]]) #Bicycle model uses a different coordinate system next_loc_tmp, _, _ = self.ego_model.forward(loc_temp, yaw, speed, action) next_loc = np.array([-next_loc_tmp[1], next_loc_tmp[0]]) self.gps_buffer[i] = next_loc return None ================================================ FILE: open_loop_training/__init__.py ================================================ ================================================ FILE: open_loop_training/code/__init__.py ================================================ from .datasets.pipelines import * from .datasets import CarlaDataset from .model_code.backbones import * from .model_code.dense_heads import * from .encoder_decoder_framework import * ================================================ FILE: open_loop_training/code/apis/__init__.py ================================================ from .train import custom_train_model from .mmdet_train import custom_train_detector __all__ = ['custom_train_model', 'custom_train_detector'] ================================================ FILE: open_loop_training/code/apis/mmdet_train.py ================================================ # --------------------------------------------- # Copyright (c) OpenMMLab. All rights reserved. # --------------------------------------------- # Modified by Zhiqi Li # --------------------------------------------- import random import warnings import numpy as np import torch import torch.distributed as dist from mmcv.parallel import MMDataParallel, MMDistributedDataParallel from mmcv.runner import (HOOKS, DistSamplerSeedHook, EpochBasedRunner, Fp16OptimizerHook, OptimizerHook, build_optimizer, build_runner, get_dist_info) from mmcv.utils import build_from_cfg from mmdet.core import EvalHook from mmdet.datasets import (build_dataset, replace_ImageToTensor) from mmdet.utils import get_root_logger import time import os.path as osp from ..datasets.builder import build_dataloader from ..core.evaluation.eval_hooks import CustomDistEvalHook, CustomEvalHook from ..datasets import custom_build_dataset def custom_train_detector(model, dataset, cfg, distributed=False, validate=False, timestamp=None, eval_model=None, meta=None): logger = get_root_logger(cfg.log_level) # prepare data loaders dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset] #assert len(dataset)==1s if 'imgs_per_gpu' in cfg.data: logger.warning('"imgs_per_gpu" is deprecated in MMDet V2.0. ' 'Please use "samples_per_gpu" instead') if 'samples_per_gpu' in cfg.data: logger.warning( f'Got "imgs_per_gpu"={cfg.data.imgs_per_gpu} and ' f'"samples_per_gpu"={cfg.data.samples_per_gpu}, "imgs_per_gpu"' f'={cfg.data.imgs_per_gpu} is used in this experiments') else: logger.warning( 'Automatically set "samples_per_gpu"="imgs_per_gpu"=' f'{cfg.data.imgs_per_gpu} in this experiments') cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu data_loaders = [ build_dataloader( ds, cfg.data.samples_per_gpu, cfg.data.workers_per_gpu, # cfg.gpus will be ignored if distributed len(cfg.gpu_ids), dist=distributed, seed=cfg.seed, shuffler_sampler=cfg.data.shuffler_sampler, # dict(type='DistributedGroupSampler'), nonshuffler_sampler=cfg.data.nonshuffler_sampler, # dict(type='DistributedSampler'), ) for ds in dataset ] # put model on gpus if distributed: find_unused_parameters = True#cfg.get('find_unused_parameters', False) # Sets the `find_unused_parameters` parameter in # torch.nn.parallel.DistributedDataParallel model = MMDistributedDataParallel( model.cuda(), device_ids=[torch.cuda.current_device()], broadcast_buffers=False, find_unused_parameters=find_unused_parameters) if eval_model is not None: eval_model = MMDistributedDataParallel( eval_model.cuda(), device_ids=[torch.cuda.current_device()], broadcast_buffers=False, find_unused_parameters=find_unused_parameters) if hasattr(cfg, 'SyncBN') and cfg.SyncBN: model = torch.nn.SyncBatchNorm.convert_sync_batchnorm(model) else: model = MMDataParallel( model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids) if eval_model is not None: eval_model = MMDataParallel( eval_model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids) # build runner optimizer = build_optimizer(model, cfg.optimizer) if 'runner' not in cfg: cfg.runner = { 'type': 'EpochBasedRunner', 'max_epochs': cfg.total_epochs } warnings.warn( 'config is now expected to have a `runner` section, ' 'please set `runner` in your config.', UserWarning) else: if 'total_epochs' in cfg: assert cfg.total_epochs == cfg.runner.max_epochs if eval_model is not None: runner = build_runner( cfg.runner, default_args=dict( model=model, eval_model=eval_model, optimizer=optimizer, work_dir=cfg.work_dir, logger=logger, meta=meta)) else: runner = build_runner( cfg.runner, default_args=dict( model=model, optimizer=optimizer, work_dir=cfg.work_dir, logger=logger, meta=meta)) # an ugly workaround to make .log and .log.json filenames the same runner.timestamp = timestamp # fp16 setting fp16_cfg = cfg.get('fp16', None) if fp16_cfg is not None: optimizer_config = Fp16OptimizerHook( **cfg.optimizer_config, **fp16_cfg, distributed=distributed) elif distributed and 'type' not in cfg.optimizer_config: optimizer_config = OptimizerHook(**cfg.optimizer_config) else: optimizer_config = cfg.optimizer_config # register hooks runner.register_training_hooks(cfg.lr_config, optimizer_config, cfg.checkpoint_config, cfg.log_config, cfg.get('momentum_config', None)) # register profiler hook #trace_config = dict(type='tb_trace', dir_name='work_dir') #profiler_config = dict(on_trace_ready=trace_config) #runner.register_profiler_hook(profiler_config) if distributed: if isinstance(runner, EpochBasedRunner): runner.register_hook(DistSamplerSeedHook()) # register eval hooks if validate: # Support batch_size > 1 in validation # val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1) # if val_samples_per_gpu > 1: # assert False # # Replace 'ImageToTensor' to 'DefaultFormatBundle' # cfg.data.val.pipeline = replace_ImageToTensor( # cfg.data.val.pipeline) val_dataset = custom_build_dataset(cfg.data.val, dict(test_mode=True)) val_dataloader = build_dataloader( val_dataset, samples_per_gpu=cfg.data.samples_per_gpu, workers_per_gpu=cfg.data.workers_per_gpu, dist=distributed, shuffle=False, shuffler_sampler=cfg.data.shuffler_sampler, # dict(type='DistributedGroupSampler'), nonshuffler_sampler=cfg.data.nonshuffler_sampler, # dict(type='DistributedSampler'), ) eval_cfg = cfg.get('evaluation', {}) eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner' eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_')) eval_hook = CustomDistEvalHook if distributed else CustomEvalHook runner.register_hook(eval_hook(val_dataloader, **eval_cfg)) # user-defined hooks if cfg.get('custom_hooks', None): custom_hooks = cfg.custom_hooks assert isinstance(custom_hooks, list), \ f'custom_hooks expect list type, but got {type(custom_hooks)}' for hook_cfg in cfg.custom_hooks: assert isinstance(hook_cfg, dict), \ 'Each item in custom_hooks expects dict type, but got ' \ f'{type(hook_cfg)}' hook_cfg = hook_cfg.copy() priority = hook_cfg.pop('priority', 'NORMAL') hook = build_from_cfg(hook_cfg, HOOKS) runner.register_hook(hook, priority=priority) if cfg.resume_from: runner.resume(cfg.resume_from) elif cfg.load_from: runner.load_checkpoint(cfg.load_from) runner.run(data_loaders, cfg.workflow) ================================================ FILE: open_loop_training/code/apis/train.py ================================================ # --------------------------------------------- # Copyright (c) OpenMMLab. All rights reserved. # --------------------------------------------- # Modified by Zhiqi Li # --------------------------------------------- from .mmdet_train import custom_train_detector from mmseg.apis import train_segmentor from mmdet.apis import train_detector def custom_train_model(model, dataset, cfg, distributed=False, validate=False, timestamp=None, eval_model=None, meta=None): """A function wrapper for launching model training according to cfg. Because we need different eval_hook in runner. Should be deprecated in the future. """ if cfg.model.type in ['EncoderDecoder3D']: assert False else: custom_train_detector( model, dataset, cfg, distributed=distributed, validate=validate, timestamp=timestamp, eval_model=eval_model, meta=meta) def train_model(model, dataset, cfg, distributed=False, validate=False, timestamp=None, meta=None): """A function wrapper for launching model training according to cfg. Because we need different eval_hook in runner. Should be deprecated in the future. """ if cfg.model.type in ['EncoderDecoder3D']: train_segmentor( model, dataset, cfg, distributed=distributed, validate=validate, timestamp=timestamp, meta=meta) else: train_detector( model, dataset, cfg, distributed=distributed, validate=validate, timestamp=timestamp, meta=meta) ================================================ FILE: open_loop_training/code/core/evaluation/__init__.py ================================================ from .eval_hooks import CustomDistEvalHook, CustomEvalHook from .epoch_hook import MySetEpochInfoHook ================================================ FILE: open_loop_training/code/core/evaluation/epoch_hook.py ================================================ from mmcv.parallel import is_module_wrapper from mmcv.runner import HOOKS, Hook @HOOKS.register_module() class MySetEpochInfoHook(Hook): """Set runner's epoch information to the model.""" def before_train_epoch(self, runner): epoch = runner.epoch model = runner.model if is_module_wrapper(model): model = model.module model.set_epoch(epoch) ================================================ FILE: open_loop_training/code/core/evaluation/eval_hooks.py ================================================ # Note: Considering that MMCV's EvalHook updated its interface in V1.3.16, # in order to avoid strong version dependency, we did not directly # inherit EvalHook but BaseDistEvalHook. import bisect import os.path as osp import re import mmcv import torch.distributed as dist from mmcv.runner import DistEvalHook as BaseDistEvalHook from mmcv.runner import EvalHook as BaseEvalHook from torch.nn.modules.batchnorm import _BatchNorm from mmdet.core.evaluation.eval_hooks import DistEvalHook, EvalHook import torch def _calc_dynamic_intervals(start_interval, dynamic_interval_list): assert mmcv.is_list_of(dynamic_interval_list, tuple) dynamic_milestones = [0] dynamic_milestones.extend( [dynamic_interval[0] for dynamic_interval in dynamic_interval_list]) dynamic_intervals = [start_interval] dynamic_intervals.extend( [dynamic_interval[1] for dynamic_interval in dynamic_interval_list]) return dynamic_milestones, dynamic_intervals class CustomEvalHook(BaseEvalHook): def __init__(self, *args, dynamic_intervals=None, **kwargs): super(CustomEvalHook, self).__init__(*args, **kwargs) self.use_dynamic_intervals = dynamic_intervals is not None if self.use_dynamic_intervals: self.dynamic_milestones, self.dynamic_intervals = \ _calc_dynamic_intervals(self.interval, dynamic_intervals) def _decide_interval(self, runner): if self.use_dynamic_intervals: progress = runner.epoch if self.by_epoch else runner.iter step = bisect.bisect(self.dynamic_milestones, (progress + 1)) # Dynamically modify the evaluation interval self.interval = self.dynamic_intervals[step - 1] def before_train_epoch(self, runner): """Evaluate the model only at the start of training by epoch.""" self._decide_interval(runner) super().before_train_epoch(runner) def before_train_iter(self, runner): self._decide_interval(runner) super().before_train_iter(runner) def _do_evaluate(self, runner): """perform evaluation and save ckpt.""" # Synchronization of BatchNorm's buffer (running_mean # and running_var) is not supported in the DDP of pytorch, # which may cause the inconsistent performance of models in # different ranks, so we broadcast BatchNorm's buffers # of rank 0 to other ranks to avoid this. if not self._should_evaluate(runner): return results = {} calculated_num = 0.0 dataset = self.dataloader.dataset prog_bar = mmcv.ProgressBar(len(dataset)) runner.model.eval() for i, data in enumerate(self.dataloader): with torch.no_grad(): result = runner.model(return_loss=False, **data) batch_size = result["num_samples"] for key in result["log_vars"]: if key not in results: results[key] = 0.0 results[key] += result["log_vars"][key] * batch_size calculated_num += batch_size for key in results.keys(): results[key] /= calculated_num print('\n') runner.log_buffer.output['eval_iter_num'] = len(self.dataloader) for name, val in results.items(): runner.log_buffer.output[name] = val runner.log_buffer.ready = True if self.save_best: self._save_ckpt(runner, results) class CustomDistEvalHook(BaseDistEvalHook): def __init__(self, *args, dynamic_intervals=None, **kwargs): super(CustomDistEvalHook, self).__init__(*args, **kwargs) self.use_dynamic_intervals = dynamic_intervals is not None if self.use_dynamic_intervals: self.dynamic_milestones, self.dynamic_intervals = \ _calc_dynamic_intervals(self.interval, dynamic_intervals) def _decide_interval(self, runner): if self.use_dynamic_intervals: progress = runner.epoch if self.by_epoch else runner.iter step = bisect.bisect(self.dynamic_milestones, (progress + 1)) # Dynamically modify the evaluation interval self.interval = self.dynamic_intervals[step - 1] def before_train_epoch(self, runner): """Evaluate the model only at the start of training by epoch.""" self._decide_interval(runner) super().before_train_epoch(runner) def before_train_iter(self, runner): self._decide_interval(runner) super().before_train_iter(runner) def _do_evaluate(self, runner): """perform evaluation and save ckpt.""" # Synchronization of BatchNorm's buffer (running_mean # and running_var) is not supported in the DDP of pytorch, # which may cause the inconsistent performance of models in # different ranks, so we broadcast BatchNorm's buffers # of rank 0 to other ranks to avoid this. if self.broadcast_bn_buffer: model = runner.model for name, module in model.named_modules(): if isinstance(module, _BatchNorm) and module.track_running_stats: dist.broadcast(module.running_var, 0) dist.broadcast(module.running_mean, 0) if not self._should_evaluate(runner): return tmpdir = self.tmpdir if tmpdir is None: tmpdir = osp.join(runner.work_dir, '.eval_hook') from .eval_tool import custom_multi_gpu_test with torch.no_grad(): results = custom_multi_gpu_test( runner.model, self.dataloader, tmpdir=tmpdir, gpu_collect=self.gpu_collect) if runner.rank == 0: print('\n') runner.log_buffer.output['eval_iter_num'] = len(self.dataloader) for name, val in results.items(): runner.log_buffer.output[name] = val runner.log_buffer.ready = True if self.save_best: self._save_ckpt(runner, results) ================================================ FILE: open_loop_training/code/core/evaluation/eval_tool.py ================================================ # --------------------------------------------- # Copyright (c) OpenMMLab. All rights reserved. # --------------------------------------------- # Modified by Zhiqi Li # --------------------------------------------- import os.path as osp import pickle import shutil import tempfile import time import mmcv import torch import torch.distributed as dist from mmcv.image import tensor2imgs from mmcv.runner import get_dist_info from mmdet.core import encode_mask_results import mmcv import numpy as np import pycocotools.mask as mask_util # --------------------------------------------- # Copyright (c) OpenMMLab. All rights reserved. # --------------------------------------------- # Modified by Zhiqi Li # Modified then by Xiaosong Jia # --------------------------------------------- import os.path as osp import pickle import shutil import tempfile import time from unittest import result import mmcv import torch import torch.distributed as dist from mmcv.image import tensor2imgs from mmcv.runner import get_dist_info from mmdet.core import encode_mask_results import mmcv import numpy as np import pycocotools.mask as mask_util def custom_encode_mask_results(mask_results): """Encode bitmap mask to RLE code. Semantic Masks only Args: mask_results (list | tuple[list]): bitmap mask results. In mask scoring rcnn, mask_results is a tuple of (segm_results, segm_cls_score). Returns: list | tuple: RLE encoded mask. """ cls_segms = mask_results num_classes = len(cls_segms) encoded_mask_results = [] for i in range(len(cls_segms)): encoded_mask_results.append( mask_util.encode( np.array( cls_segms[i][:, :, np.newaxis], order='F', dtype='uint8'))[0]) # encoded with RLE return [encoded_mask_results] def custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False): """Test model with multiple gpus. This method tests model with multiple gpus and collects the results under two different modes: gpu and cpu modes. By setting 'gpu_collect=True' it encodes results to gpu tensors and use gpu communication for results collection. On cpu mode it saves the results on different gpus to 'tmpdir' and collects them by the rank 0 worker. Args: model (nn.Module): Model to be tested. data_loader (nn.Dataloader): Pytorch data loader. tmpdir (str): Path of directory to save the temporary results from different gpus under cpu mode. gpu_collect (bool): Option to use either gpu or cpu to collect results. Returns: list: The prediction results. """ model.eval() results = {} calculated_num = 0.0 dataset = data_loader.dataset rank, world_size = get_dist_info() # if rank == 0: # prog_bar = mmcv.ProgressBar(len(dataset)) time.sleep(2) # This line can prevent deadlock problem in some cases. for i, data in enumerate(data_loader): with torch.no_grad(): result = model(return_loss=False, **data) batch_size = result["num_samples"] for key in result["log_vars"]: if key not in results: results[key] = 0.0 results[key] += result["log_vars"][key] * batch_size calculated_num += batch_size # if rank == 0: # for _ in range(batch_size * world_size): # prog_bar.update() for key in results.keys(): results[key] = (results[key]/calculated_num, calculated_num) # collect results from all ranks if gpu_collect: results = collect_results_gpu(results, len(dataset)) else: results = collect_results_cpu(results, len(dataset), tmpdir) tmpdir = tmpdir+'_mask' if tmpdir is not None else None return results def collect_results_cpu(result_part, size, tmpdir=None): rank, world_size = get_dist_info() # create a tmp dir if it is not specified if tmpdir is None: MAX_LEN = 512 # 32 is whitespace dir_tensor = torch.full((MAX_LEN, ), 32, dtype=torch.uint8, device='cuda') if rank == 0: mmcv.mkdir_or_exist('.dist_test') tmpdir = tempfile.mkdtemp(dir='.dist_test') tmpdir = torch.tensor( bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda') dir_tensor[:len(tmpdir)] = tmpdir dist.broadcast(dir_tensor, 0) tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip() else: mmcv.mkdir_or_exist(tmpdir) # dump the part result to the dir mmcv.dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl')) dist.barrier() # collect all parts if rank != 0: return None else: # load results of all parts from tmp dir results = {} results_cnts = {} num_sample = 0 for i in range(world_size): part_file = osp.join(tmpdir, f'part_{i}.pkl') part_file = mmcv.load(part_file) for key in part_file: if key not in results: results[key] = 0.0 results_cnts[key] = 0.0 results[key] += part_file[key][0] * part_file[key][1] results_cnts[key] += part_file[key][1] for key in results: results[key] /= results_cnts[key] shutil.rmtree(tmpdir) return results def collect_results_gpu(result_part, size): collect_results_cpu(result_part, size) ================================================ FILE: open_loop_training/code/datasets/__init__.py ================================================ from .carla_dataset import CarlaDataset from .builder import custom_build_dataset __all__ = [ "CarlaDataset" ] ================================================ FILE: open_loop_training/code/datasets/base_dataset.py ================================================ # Copyright (c) OpenMMLab. All rights reserved. import copy import warnings import os.path as osp from abc import ABCMeta, abstractmethod from os import PathLike from typing import List import mmcv import numpy as np from torch.utils.data import Dataset from mmdet3d.datasets.pipelines import Compose def expanduser(path): if isinstance(path, (str, PathLike)): return osp.expanduser(path) else: return path class BaseDataset(Dataset): """Base dataset. Args: data_prefix (str): the prefix of data path pipeline (list): a list of dict, where each element represents a operation defined in `mmcls.datasets.pipelines` ann_file (str | None): the annotation file. When ann_file is str, the subclass is expected to read from the ann_file. When ann_file is None, the subclass is expected to read according to data_prefix test_mode (bool): in train mode or test mode """ def __init__(self, ann_file, pipeline, data_prefix='', test_mode=False): super(BaseDataset, self).__init__() self.data_prefix = expanduser(data_prefix) self.pipeline = Compose(pipeline) self.ann_file = expanduser(ann_file) self.test_mode = test_mode self.data_infos = [] @abstractmethod def load_annotations(self): return mmcv.load(self.ann_file) def pre_pipeline(self, results): """Prepare results dict for pipeline.""" results['img_prefix'] = self.img_prefix def __len__(self): return len(self.data_infos) def __getitem__(self, idx): results = copy.deepcopy(self.data_infos[idx]) self.pre_pipeline(results) return self.pipeline(results) def evaluate(self, results, metric='accuracy', metric_options=None, jsonfile_prefix=None, indices=None, logger=None): pass ================================================ FILE: open_loop_training/code/datasets/builder.py ================================================ # Copyright (c) OpenMMLab. All rights reserved. import copy import platform import random from functools import partial import numpy as np from mmcv.parallel import collate from mmcv.runner import get_dist_info from mmcv.utils import Registry, build_from_cfg from torch.utils.data import DataLoader from mmdet.datasets.samplers import GroupSampler from ..datasets.samplers.group_sampler import DistributedGroupSampler from ..datasets.samplers.distributed_sampler import DistributedSampler from ..datasets.samplers.sampler import build_sampler def build_dataloader(dataset, samples_per_gpu, workers_per_gpu, num_gpus=1, dist=True, shuffle=True, seed=None, shuffler_sampler=None, nonshuffler_sampler=None, **kwargs): """Build PyTorch DataLoader. In distributed training, each GPU/process has a dataloader. In non-distributed training, there is only one dataloader for all GPUs. Args: dataset (Dataset): A PyTorch dataset. samples_per_gpu (int): Number of training samples on each GPU, i.e., batch size of each GPU. workers_per_gpu (int): How many subprocesses to use for data loading for each GPU. num_gpus (int): Number of GPUs. Only used in non-distributed training. dist (bool): Distributed training/test or not. Default: True. shuffle (bool): Whether to shuffle the data at every epoch. Default: True. kwargs: any keyword argument to be used to initialize DataLoader Returns: DataLoader: A PyTorch dataloader. """ rank, world_size = get_dist_info() if dist: # DistributedGroupSampler will definitely shuffle the data to satisfy # that images on each GPU are in the same group if shuffle: sampler = build_sampler(shuffler_sampler if shuffler_sampler is not None else dict(type='DistributedGroupSampler'), dict( dataset=dataset, samples_per_gpu=samples_per_gpu, num_replicas=world_size, rank=rank, seed=seed) ) else: sampler = build_sampler(nonshuffler_sampler if nonshuffler_sampler is not None else dict(type='DistributedSampler'), dict( dataset=dataset, num_replicas=world_size, rank=rank, shuffle=shuffle, seed=seed) ) batch_size = samples_per_gpu num_workers = workers_per_gpu else: # assert False, 'not support in bevformer' print('WARNING!!!!, Only can be used for obtain inference speed!!!!') sampler = GroupSampler(dataset, samples_per_gpu) if shuffle else None batch_size = num_gpus * samples_per_gpu num_workers = num_gpus * workers_per_gpu init_fn = partial( worker_init_fn, num_workers=num_workers, rank=rank, seed=seed) if seed is not None else None data_loader = DataLoader( dataset, batch_size=batch_size, sampler=sampler, num_workers=num_workers, collate_fn=partial(collate, samples_per_gpu=samples_per_gpu), pin_memory=False, worker_init_fn=init_fn, drop_last = True, **kwargs) return data_loader def worker_init_fn(worker_id, num_workers, rank, seed): # The seed of each worker equals to # num_worker * rank + worker_id + user_seed worker_seed = num_workers * rank + worker_id + seed np.random.seed(worker_seed) random.seed(worker_seed) # Copyright (c) OpenMMLab. All rights reserved. import platform from mmcv.utils import Registry, build_from_cfg from mmdet.datasets import DATASETS from mmdet.datasets.builder import _concat_dataset if platform.system() != 'Windows': # https://github.com/pytorch/pytorch/issues/973 import resource rlimit = resource.getrlimit(resource.RLIMIT_NOFILE) base_soft_limit = rlimit[0] hard_limit = rlimit[1] soft_limit = min(max(4096, base_soft_limit), hard_limit) resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit)) OBJECTSAMPLERS = Registry('Object sampler') def custom_build_dataset(cfg, default_args=None): from mmdet3d.datasets.dataset_wrappers import CBGSDataset from mmdet.datasets.dataset_wrappers import (ClassBalancedDataset, ConcatDataset, RepeatDataset) if isinstance(cfg, (list, tuple)): dataset = ConcatDataset([custom_build_dataset(c, default_args) for c in cfg]) elif cfg['type'] == 'ConcatDataset': dataset = ConcatDataset( [custom_build_dataset(c, default_args) for c in cfg['datasets']], cfg.get('separate_eval', True)) elif cfg['type'] == 'RepeatDataset': dataset = RepeatDataset( custom_build_dataset(cfg['dataset'], default_args), cfg['times']) elif cfg['type'] == 'ClassBalancedDataset': dataset = ClassBalancedDataset( custom_build_dataset(cfg['dataset'], default_args), cfg['oversample_thr']) elif cfg['type'] == 'CBGSDataset': dataset = CBGSDataset(custom_build_dataset(cfg['dataset'], default_args)) elif isinstance(cfg.get('ann_file'), (list, tuple)): dataset = _concat_dataset(cfg, default_args) else: dataset = build_from_cfg(cfg, DATASETS, default_args) return dataset ================================================ FILE: open_loop_training/code/datasets/carla_dataset.py ================================================ import os from unittest import result import cv2 import copy import mmcv import torch import random import numpy as np from PIL import Image import matplotlib.pyplot as plt from torchvision import transforms as T from nuscenes.eval.common.utils import Quaternion import pickle from mmcv.parallel import DataContainer as DC from mmdet.datasets import DATASETS, CustomDataset from mmdet3d.datasets.pipelines import Compose from .base_dataset import BaseDataset import json import math import io @DATASETS.register_module() class CarlaDataset(BaseDataset): r"""Carla Dataset. """ def __init__(self, cfg, used_town, pipeline, is_local, full_queue_pipeline, test_mode=False, **kwargs): super(CarlaDataset).__init__() self.test_mode = test_mode self.pred_len = cfg["pred_len"] ## Pipeline for single frame self.pipeline = Compose(pipeline) ## Pipeline for a sequence of history frames self.full_queue_pipeline = Compose(full_queue_pipeline) self.resize_to21x21 = T.Resize(size=(21, 21)) self.is_local = bool(cfg['is_local']) ## Ignore this, we train out model on a cluster with ceph self.is_full = False ## 189K or 2M dataset if "is_full" in cfg: self.is_full = bool(cfg["is_full"]) ## 2M frames dataset setting dataset_size_fname = "dataset_metadata.pkl" with open("../dataset/"+dataset_size_fname, "rb") as f: route_length_dict = pickle.load(f) self.history_query_index_lis = cfg["history_query_index_lis"] route_start_index = -self.history_query_index_lis[0] self.data_infos = [] #tuple: (route_folder, current_timestep) ### Prepare for dataloader to shuffle data town_sampel_cnt_dict = {} for single_used_town in used_town: if single_used_town not in route_length_dict: ## No data collected print(single_used_town, "Not Found") continue now_town = single_used_town[:6] ## town_name without index if now_town not in town_sampel_cnt_dict: town_sampel_cnt_dict[now_town] = 0 is_val_town = ("02" in now_town or "05" in now_town) ##When we only use the 189K dataset if (not self.is_full or is_val_town) and town_sampel_cnt_dict[now_town] > cfg["max_sample_per_town"][now_town]: continue for route in route_length_dict[single_used_town]: ##When we only use the 189K dataset if (not self.is_full or is_val_town) and town_sampel_cnt_dict[now_town] > cfg["max_sample_per_town"][now_town]: break ##Not use the first few frames if route_length_dict[single_used_town][route] < route_start_index+1+self.pred_len: continue if self.is_local: route_path = route[:3] + "dataset/"+route[3:] else: route_path = route new_data_info = [(route_path, current_time_step) for current_time_step in range(route_start_index, route_length_dict[single_used_town][route]-self.pred_len)] self.data_infos += new_data_info town_sampel_cnt_dict[now_town] += len(new_data_info) print(town_sampel_cnt_dict) if not self.is_local: ## ignore this line (we train our model on a cluster with ceph) ceph_conf = '~/petreloss.conf' from petrel_client.client import Client self.client = Client(ceph_conf) self.flag = np.ones(len(self), dtype=np.uint8) self.cfg = cfg def load_json(self, fname): if self.is_local: with open(fname, "r") as f: return json.load(f) else: return json.loads(self.client.get(fname)) def load_npy(self, fname): if self.is_local: with open(fname, "rb") as f: return np.load(fname, allow_pickle=True) else: return np.load(io.BytesIO(self.client.get(fname)), allow_pickle=True) def offset_then_rotate(self, target_2d_world_coor, ref_2d_wolrd_coor, ref_yaw): final_coor = target_2d_world_coor - ref_2d_wolrd_coor R = np.array([ [np.cos(ref_yaw), -np.sin(ref_yaw)], [np.sin(ref_yaw), np.cos(ref_yaw)] ]) return np.einsum("ij,kj->ki", R.T, final_coor) ## Preprocess for single frame def get_data_info(self, data_folder, route_index, is_current): results = {} results["scene_token"] = data_folder results["frame_idx"] = route_index measurements = self.load_json(os.path.join(data_folder, "measurements", f"{str(route_index).zfill(4)}.json")) ego_theta = measurements["theta"] if not np.isnan(measurements["theta"]) else 0# fix for theta=nan in some measurements ego_theta = ego_theta - np.pi/2 #Follow https://github.com/dotchen/LAV/blob/23e2f1be3b1b43593761bc7ea7beabda1086b253/team_code/lav_agent.py results["input_theta"] = ego_theta results["input_x"] = measurements["y"] ## All coordinates are in the ego coordinate system (go front=vertically up in BEV similar to Roach) results["input_y"] = -measurements["x"] ## All coordinates are in the ego coordinate system (go front=vertically up in BEV similar to Roach) ego_xy = np.stack([results["input_x"], results["input_y"]], axis=-1) if is_current: future_measurements_lis = [] for future_index in range(1, self.pred_len+1): future_measurements_lis.append(self.load_json(os.path.join(data_folder, "measurements", f"{str(route_index+future_index).zfill(4)}.json"))) future_x = np.array([_["y"] for _ in future_measurements_lis]) future_y = -np.array([_["x"] for _ in future_measurements_lis]) results['waypoints'] = self.offset_then_rotate(np.stack([future_x, future_y], axis=-1), ego_xy, ego_theta) results["future_speed"] = [_["speed"] for _ in future_measurements_lis] results["speed"] = measurements["speed"] results["can_bus"] = np.zeros(18) results["can_bus"][0] = results["input_x"] ## Gloabal Coordinate results["can_bus"][1] = results["input_y"] ## Global Coordinate accel = np.array(measurements["acceleration"]) accel[:2] = self.offset_then_rotate(np.array(accel[:2])[np.newaxis, :], np.array([0, 0]), ego_theta).squeeze(0) results["can_bus"][7:10] = accel results["can_bus"][10:13] = measurements["angular_velocity"] results["can_bus"][13] = measurements["speed"] results["can_bus"][-2] = ego_theta results["can_bus"][-1] = ego_theta / np.pi * 180 x_target = measurements["y_target"] ## All coordinates are in the ego coordinate system (go front=vertically up in BEV similar to Roach) y_target = -measurements["x_target"] ## All coordinates are in the ego coordinate system (go front=vertically up in BEV similar to Roach) results['target_point'] = self.offset_then_rotate(np.array([[x_target, y_target]]), ego_xy, ego_theta).squeeze(0) results['target_point_aim'] = results["target_point"] # VOID = -1 # LEFT = 1 # RIGHT = 2 # STRAIGHT = 3 # LANEFOLLOW = 4 # CHANGELANELEFT = 5 # CHANGELANERIGHT = 6 command = measurements["target_command"] if command < 0: command = 4 command -= 1 results['target_command_raw'] = torch.tensor(command).long() assert command in [0, 1, 2, 3, 4, 5] cmd_one_hot = [0] * 6 cmd_one_hot[command] = 1 results['target_command'] = torch.tensor(cmd_one_hot) results["pts_filename"] = os.path.join(data_folder, "lidar", f"{str(route_index).zfill(4)}.npy") if is_current: ##Distill Feature current_supervision = self.load_npy(os.path.join(data_folder, "supervision", f"{str(route_index).zfill(4)}.npy")).item() ## [throttle, steer, brake] results["action"] = current_supervision["action"] results["action_mu"] = current_supervision["action_mu"] results["action_sigma"] = current_supervision["action_sigma"] ## Brake by rules if current_supervision['only_ap_brake']: results['action_mu'][0] = 0.8 results['action_sigma'][0] = 5.5 ## Label future_supervision_lis = [] for future_index in range(1, self.pred_len+1): future_supervision_lis.append(self.load_npy(os.path.join(data_folder, "supervision", f"{str(route_index+future_index).zfill(4)}.npy")).item()) future_only_ap_brake = [_["only_ap_brake"] for _ in future_supervision_lis] results['future_action_mu'] = [_["action_mu"] for _ in future_supervision_lis] ## pred_len x 2 results['future_action_sigma'] =[_["action_sigma"] for _ in future_supervision_lis] ## pred_len x 2 results['future_action'] = np.stack([_["action"] for _ in future_supervision_lis], axis=0) ## pred_len x (control.throttle, control.steer, control.brake) # use the average value of roach braking action when the brake is only performed by the rule-based detector for future_index in range(self.pred_len): if future_only_ap_brake[future_index]: results['future_action_mu'][future_index][0] = 0.8 results['future_action_sigma'][future_index][0] = 5.5 results["value"] = current_supervision["value"] results["feature"] = current_supervision["features"] results["grid_feature"] = current_supervision["cnn_features"] results["future_feature"] = [_["features"] for _ in future_supervision_lis] results["future_value"] = [_["value"] for _ in future_supervision_lis] results["future_grid_feature"] = [_["cnn_features"] for _ in future_supervision_lis] return results def prepare_train_data(self, index): """Returns the item at index idx. """ data_queue = [] # temporal aug # random choose 3 frames from last 4 frames #prev_indexs_list = list(range(index-self.queue_length, index)) #random.shuffle(prev_indexs_list) #prev_indexs_list = sorted(prev_indexs_list[1:], reverse=True) prev_indexs_list = self.history_query_index_lis data_folder, route_index = self.data_infos[index] input_dict = self.get_data_info(data_folder, route_index, is_current=True) if input_dict is None: return None example = self.pipeline(input_dict) data_queue.insert(0, example) # Load prev frames, not load the current for i in prev_indexs_list[:-1][::-1]: input_dict = self.get_data_info(data_folder, route_index + i, is_current=False) input_dict["is_local"] = self.is_local example = self.pipeline(input_dict) data_queue.insert(0, copy.deepcopy(example)) return union2one(self.full_queue_pipeline, data_queue) def __getitem__(self, idx): while True: data = self.prepare_train_data(idx) if data is None: idx = self._rand_another(idx) continue return data def _rand_another(self, idx): """Randomly get another item with the same flag. Returns: int: Another index of item with the same flag. """ pool = np.where(self.flag == self.flag[idx])[0] return np.random.choice(pool) def prepare_test_data(self, index): input_dict = self.get_data_info(index) example = self.pipeline(input_dict) return example def get_ego_shift(delta_x, delta_y, ego_angle): # obtain rotation angle and shift with ego motion translation_length = np.sqrt(delta_x ** 2 + delta_y ** 2) translation_angle = np.arctan2(delta_y, delta_x) / np.pi * 180 bev_angle = ego_angle - translation_angle shift_y = translation_length * np.cos(bev_angle / 180 * np.pi) shift_x = translation_length * np.sin(bev_angle / 180 * np.pi) return shift_x, shift_y ### Multiple frames def union2one(full_queue_pipeline, queue): queue = full_queue_pipeline(queue) imgs_list = torch.stack([each['img'] for each in queue]) points_size = [each['points'].data.shape[0] for each in queue] metas_map = [] prev_pos = None prev_angle = None for i, each in enumerate(queue): meta = copy.deepcopy(each['img_metas'].data) meta['points_size'] = points_size if i == 0: ## Current Frame meta['prev_bev'] = False prev_pos = copy.deepcopy(meta['can_bus'][:3]) prev_angle = copy.deepcopy(meta['can_bus'][-1]) meta['can_bus'][:3] = 0 meta['can_bus'][-1] = 0 else: meta['prev_bev'] = True tmp_pos = copy.deepcopy(meta['can_bus'][:3]) tmp_angle = copy.deepcopy(meta['can_bus'][-1]) meta['can_bus'][:3] -= prev_pos meta['can_bus'][-1] -= prev_angle prev_pos = copy.deepcopy(tmp_pos) prev_angle = copy.deepcopy(tmp_angle) metas_map.append(meta) # sweep2key transformation metas_map[-1]['curr2key'] = torch.eye(4) metas_map[-1]['currlidar2keycam'] = metas_map[-1]['lidar2cam'] key_x, key_y = queue[-1]['img_metas'].data['can_bus'][:2] key_yaw = queue[-1]['img_metas'].data['can_bus'][-2] for i in range(len(queue)-2, -1, -1): curr_x = queue[i]['img_metas'].data['can_bus'][0] curr_y = queue[i]['img_metas'].data['can_bus'][1] curr2key_x, curr2key_y = get_ego_shift( key_x - curr_x, key_y - curr_y, key_yaw / np.pi * 180 ) curr_yaw = queue[i]['img_metas'].data['can_bus'][-2] curr2key_angle = key_yaw - curr_yaw # get transmation mats R = torch.eye(4) R[:2,:2] = torch.Tensor([[np.cos(curr2key_angle), np.sin(curr2key_angle)], [-np.sin(curr2key_angle), np.cos(curr2key_angle)]]) T = torch.eye(4) T[0,3], T[1,3] = curr2key_x, curr2key_y curr2key = R @ T metas_map[i]['curr2key'] = curr2key metas_map[i]['currlidar2keycam'] = metas_map[i]['lidar2cam'] @ curr2key # dense-fusion points = queue[-1]['points'].data points = torch.cat([points,torch.zeros(points.shape[0],1)], dim=1) points[:,4] = 0 points_list = [points] for i in range(len(queue)-2, -1, -1): points_sweep = copy.deepcopy(queue[i]['points'].data) points_sweep = torch.cat([points_sweep,torch.zeros(points_sweep.shape[0],1)], dim=1) curr2key = metas_map[i]['curr2key'] points_sweep[:, :4] = (curr2key@points_sweep[:, :4].T).T timestamp = i-(len(queue)-1) points_sweep[:,4] = timestamp points_list.append(points_sweep) points = torch.cat(points_list).unsqueeze(0) queue[-1]['points'] = DC(points, cpu_only=False, stack=True) queue[-1]['img'] = DC(imgs_list, cpu_only=False, stack=True) queue[-1]['img_metas'] = DC(metas_map, cpu_only=True) queue = queue[-1] return queue ================================================ FILE: open_loop_training/code/datasets/pipelines/__init__.py ================================================ from .transform import (InitMultiImage, ImageTransformMulti, IDAImageTransform) from .loading import LoadMultiImages, LoadPoints, LoadDepth from .formating import CarlaFormatBundle,CarlaCollect __all__ = [ 'LoadPoints', 'ImageTransformMulti', 'InitMultiImage', 'LoadMultiImages', 'CarlaFormatBundle', 'CarlaCollect', 'LoadDepth', 'IDAImageTransform', ] ================================================ FILE: open_loop_training/code/datasets/pipelines/formating.py ================================================ # Copyright (c) OpenMMLab. All rights reserved. import torch import numpy as np from mmcv.parallel import DataContainer as DC from mmdet3d.core.points import BasePoints from mmdet.datasets.builder import PIPELINES from mmdet.datasets.pipelines import to_tensor from torch import Tensor @PIPELINES.register_module() class CarlaFormatBundle(object): def __init__(self, ): return def __call__(self, results): if 'points' in results: if isinstance(results['points'], BasePoints): results['points'] = DC(results['points'].tensor) else: results['points'] = DC(torch.Tensor(results['points'])) if 'img' in results: if isinstance(results['img'], list): results['img'] = np.stack(results['img'], axis=0) return results def __repr__(self): return self.__class__.__name__ @PIPELINES.register_module() class CarlaCollect(object): def __init__(self, keys, meta_keys=('can_bus', 'ori_shape', 'intrin_mats', 'lidar2img', 'depth2img', 'cam2img', 'pad_shape', 'scale_factor', 'flip', 'pcd_horizontal_flip', 'pcd_vertical_flip', 'frame_idx', 'img_filename', 'img_norm_cfg', 'bda_mat', 'sample_idx', 'ida_mats', 'sensor2ego_mats', 'pts_filename', 'scene_token')): self.keys = keys self.meta_keys = meta_keys def __call__(self, results): """Call function to collect keys in results. The keys in ``meta_keys`` will be converted to :obj:`mmcv.DataContainer`. Args: results (dict): Result dict contains the data to collect. Returns: dict: The result dict contains the following keys - keys in ``self.keys`` - ``img_metas`` """ data = {} img_metas = {} for key in self.meta_keys: if key in results: img_metas[key] = results[key] data['img_metas'] = DC(img_metas, cpu_only=True) for key in self.keys: if key in results: data[key] = results[key] return data def __repr__(self): """str: Return a string that describes the module.""" return self.__class__.__name__ + \ f'(keys={self.keys}, meta_keys={self.meta_keys})' ================================================ FILE: open_loop_training/code/datasets/pipelines/loading.py ================================================ # Copyright (c) OpenMMLab. All rights reserved. import os from types import new_class import cv2 import time import copy import torch import numpy as np import os.path as osp from PIL import Image import matplotlib.pyplot as plt from mmdet.datasets.builder import PIPELINES from torchvision import transforms as T import mmcv from mmdet.datasets.builder import PIPELINES from mmcv.parallel import DataContainer as DC from mmdet3d.datasets.pipelines.loading import LoadPointsFromFile import io from scipy.ndimage import label as sep_mask @PIPELINES.register_module() class LoadMultiImages(object): def __init__(self, is_local=False, camera_names = ['rgb_front', 'rgb_left', 'rgb_right', 'rgb_back'], ceph_conf="~/petreloss.conf", ): self.is_local = is_local self.camera_names = camera_names if not self.is_local: from petrel_client.client import Client self.client = Client(ceph_conf) self.file_client_args=dict(backend='disk') self.file_client = mmcv.FileClient(**self.file_client_args) def load_img(self, filename): if self.is_local: return np.array(Image.open(filename)) else: return np.frombuffer(memoryview(self.client.get(filename)), np.uint8).reshape(900, 1600, 3) def __call__(self, results): filenames = [os.path.join(results["scene_token"], name, str(results["frame_idx"]).zfill(4)+".png") for name in self.camera_names] results['img'] = [self.load_img(filename) for filename in filenames] results["img_filename"] = filenames return results def __repr__(self): repr_str = self.__class__.__name__ repr_str += f'(is_local={self.is_local}, ' return repr_str @PIPELINES.register_module() class LoadPoints(LoadPointsFromFile): def __init__(self, is_local, ceph_conf='~/petreloss.conf', **kwargs, ): super().__init__(**kwargs) self.is_local = is_local if not self.is_local: from petrel_client.client import Client self.client = Client(ceph_conf) def _load_points(self, pts_filename): if not self.is_local: points = np.load(io.BytesIO(self.client.get(pts_filename)), allow_pickle=True) else: points = np.load(pts_filename, allow_pickle=True) return points @PIPELINES.register_module() class LoadDepth(LoadMultiImages): def __init__(self, is_local=False, # carla's camera use unreal-coordination, which must be corrected camera_names = ['rgb_front', 'rgb_left', 'rgb_right', 'rgb_back'], ceph_conf="~/petreloss.conf", ): super().__init__(is_local, camera_names, ceph_conf) def __call__(self, results): filenames = [os.path.join(results["scene_token"], name.replace('rgb','depth'), str(results["frame_idx"]).zfill(4)+".png") for name in self.camera_names] depths = [] for filename in filenames: rgb = self.load_img(filename).astype(np.float32) r,g,b = rgb[...,0], rgb[...,1], rgb[...,2] depth = (r + g*256 + b*256*256)/(256**3 - 1) * 1000 depths.append(depth) results['depth'] = depths return results ## Segment Traffic Light def red_green_yellow(rgb_image): hsv = cv2.cvtColor(rgb_image[:, None, :], cv2.COLOR_RGB2HSV) avg_saturation = int(hsv[:,:,1].mean()) # Sum the brightness values sat_low = int(avg_saturation * 1.1)#1.3) val_low = 140 # Green lower_green = np.array([70,sat_low,val_low]) upper_green = np.array([100,255,255]) sum_green = cv2.inRange(hsv, lower_green, upper_green).astype(np.bool8).sum() # Red lower_red = np.array([150,sat_low,val_low]) upper_red = np.array([180,255,255]) sum_red = cv2.inRange(hsv, lower_red, upper_red).astype(np.bool8).sum() if sum_red < 3 and sum_green < 3: return 0 #not sure or yellow if sum_red >= sum_green: return 1# Red return 2 # Green @PIPELINES.register_module() class LoadSeg(LoadMultiImages): def __init__(self, is_local=False, # carla's camera use unreal-coordination, which must be corrected camera_names = ['rgb_front', 'rgb_left', 'rgb_right', 'rgb_back'], seg_label_idxs=[0,1,2,3,4,5,6], ceph_conf="~/petreloss.conf", ): super().__init__(is_local, camera_names, ceph_conf) self.seg_label_idxs = seg_label_idxs def load_img(self, filename): if self.is_local: return np.array(Image.open(filename)) else: return np.frombuffer(memoryview(self.client.get(filename)), np.uint8).reshape(900, 1600,) def __call__(self, results): filenames = [os.path.join(results["scene_token"], name.replace('rgb','seg'), str(results["frame_idx"]).zfill(4)+".png") for name in self.camera_names] segs = [] for f_index, filename in enumerate(filenames): src = self.load_img(filename).astype(np.float32) seg = np.zeros_like(src) for idx, label in enumerate(self.seg_label_idxs): ## Mannually Segment the traffic light into red, green, yellow if label == 18: now_img = results['img'][f_index] tl_part = src==label #tl_pixel_index = np.where(tl_part) tl_mask, num_tl = sep_mask(tl_part, structure=[[1,1,1],[1,1,1],[1,1,1]]) a_flattened = tl_mask.ravel() sidx = np.argsort(a_flattened) afs = a_flattened[sidx] cut_idx = np.r_[0,np.flatnonzero(afs[1:] != afs[:-1])+1, a_flattened.size] row, col = np.unravel_index(sidx, tl_mask.shape) row_indices = [row[i:j] for i,j in zip(cut_idx[:-1],cut_idx[1:])][1:] col_indices = [col[i:j] for i,j in zip(cut_idx[:-1],cut_idx[1:])][1:] for tl_index in range(num_tl): if len(row_indices[tl_index]) < 20: continue now_tl = now_img[row_indices[tl_index], col_indices[tl_index], :] light_type=red_green_yellow(now_tl) seg[row_indices[tl_index], col_indices[tl_index]] = idx + light_type else: seg[np.where(src==label)] = idx segs.append(seg) results['seg'] = segs return results ================================================ FILE: open_loop_training/code/datasets/pipelines/transform.py ================================================ from email.mime import image import os import cv2 import copy import numpy as np from numpy import random import matplotlib.pyplot as plt from imgaug import augmenters as iaa from torchvision import transforms as T import torch import mmcv from mmdet.datasets.builder import PIPELINES from mmcv.parallel import DataContainer as DC from mmdet.datasets.pipelines import to_tensor ## Precompute the following matrice to speed LIDAR2UNREAL = { "rgb_front": np.array([[1.0, 0.0, -0.0, -1.5], [0.0, 1.0, 0.0, 0.0], [-0.0, 0.0, 1.0, -2.5], [0.0, 0.0, 0.0, 1.0]]), "rgb_back":np.array([[-1.0, -0.0, 0.0, -1.6], [0.0, -1.0, 0.0, -0.0], [0.0, 0.0, 1.0, -2.5], [0.0, 0.0, 0.0, 1.0]]), "rgb_left":np.array([[0.0, -1.0, 0.0, -0.3], [1.0, 0.0, -0.0, -0.0], [0.0, 0.0, 1.0, -2.5], [0.0, 0.0, 0.0, 1.0]]), "rgb_right":np.array([[0.0, 1.0, -0.0, -0.3], [-1.0, -0.0, 0.0, 0.0], [0.0, 0.0, 1.0, -2.5], [0.0, 0.0, 0.0, 1.0]]) } unreal2cam = np.array([[0,1,0,0], [0,0,-1,0], [1,0,0,0], [0,0,0,1]]) LIDAR2CAM = { "rgb_front": np.array([ [0.0, 1.0, 0.0, 0.0] , [0.0, 0.0, -1.0, 2.5] , [1.0, 0.0, 0.0, -1.5] , [0.0, 0.0, 0.0, 1.0] ]), "rgb_back": np.array([ [0.0, -1.0, 0.0, 0.0] , [0.0, 0.0, -1.0, 2.5] , [-1.0, 0.0, 0.0, -1.6] , [0.0, 0.0, 0.0, 1.0] ]), "rgb_left": np.array([ [1.0, 0.0, 0.0, 0.0] , [0.0, 0.0, -1.0, 2.5] , [0.0, -1.0, 0.0, -0.3] , [0.0, 0.0, 0.0, 1.0] ]), "rgb_right": np.array([ [-1.0, 0.0, 0.0, 0.0] , [0.0, 0.0, -1.0, 2.5] , [0.0, 1.0, 0.0, -0.3] , [0.0, 0.0, 0.0, 1.0] ]), } UNDISTORT_LIDAR2IMG = { "rgb_front":np.array([[788.25758876, 304.14395142, 0.0, -1182.38638314], [449.78972161, 0.0, -221.49429321, -120.94884939000008], [1.0, 0.0, 0.0, -1.5], [0.0, 0.0, 0.0, 1.0]]), "rgb_left":np.array([[304.14395142, -788.25758876, 0.0, -236.47727662799997], [0.0, -449.78972161, -221.49429321, 418.79881654199994], [0.0, -1.0, 0.0, -0.3], [0.0, 0.0, 0.0, 1.0]]), "rgb_right":np.array([[-304.14395142, 788.25758876, 0.0, -236.47727662799997], [0.0, 449.78972161, -221.49429321, 418.79881654199994], [0.0, 1.0, 0.0, -0.3], [0.0, 0.0, 0.0, 1.0]]), "rgb_back":np.array([[-788.25758876, -304.14395142, 0.0, -1261.2121420160001], [-449.78972161, 0.0, -221.49429321, -165.9278215510001], [-1.0, 0.0, 0.0, -1.6], [0.0, 0.0, 0.0, 1.0]]) } LIDAR2IMG = { "rgb_front":np.array([[800.0, 214.35935394, 0.0, -1200.0], [450.0, 0.0, -214.35935394, -139.10161515000004], [1.0, 0.0, 0.0, -1.5], [0.0, 0.0, 0.0, 1.0]]), "rgb_left":np.array([[214.35935394, -800.0, 0.0, -240.0], [0.0, -450.0, -214.35935394, 400.89838484999996], [0.0, -1.0, 0.0, -0.3], [0.0, 0.0, 0.0, 1.0]]), "rgb_right":np.array([[-214.35935394, 800.0, 0.0, -240.0], [0.0, 450.0, -214.35935394, 400.89838484999996], [0.0, 1.0, 0.0, -0.3], [0.0, 0.0, 0.0, 1.0]]), "rgb_back":np.array([[-800.0, -214.35935394, 0.0, -1280.0], [-450.0, 0.0, -214.35935394, -184.10161515000007], [-1.0, 0.0, 0.0, -1.6], [0.0, 0.0, 0.0, 1.0]]) } mtx = np.array([[214.35935394, 0, 800,],[0, 214.35935394, 450],[0, 0, 1]]) dist = np.array([[ 0.00888296, -0.00130899, 0.00012061, -0.00338673, 0.00028834]]) newcameramtx = np.array([[304.14395142, 0, 788.25758876,], [ 0, 221.49429321, 449.78972161,], [ 0, 0, 1, ],]) CAM_INTRINSIC = { "rgb_front": mtx, "rgb_back": mtx, "rgb_left": mtx, "rgb_right": mtx, } CAM_DIST= { "rgb_front": dist, "rgb_back": dist, "rgb_left": dist, "rgb_right": dist, } @PIPELINES.register_module(force=True) class InitMultiImage(object): """Random scale the image Args: scales """ def __init__(self, cfg): self.size = cfg["img_size"] self.camera_names = cfg['camera_names'] self.resize_func = T.Resize(size=self.size) assert len(self.size)==2 self.undistort = cfg["undistort"] self.unreal_coord = cfg["unreal_coord"] self.use_depth = cfg['use_depth'] ## Undistort mat mapx, mapy = cv2.initUndistortRectifyMap(mtx, dist, None, newcameramtx, (1600, 900), 5) mapx = (torch.from_numpy(mapx) - 800) / 800 mapy= (torch.from_numpy(mapy) - 450) / 450 self.num_cams = cfg["num_cams"] self.temporal_len = cfg["queue_length"] ## Precompute the mapping matrix to speed up self.map_grid = torch.stack([mapx, mapy], dim=-1).unsqueeze(0).repeat(self.temporal_len*self.num_cams, 1, 1, 1) if self.use_depth: self.map_grid_depth = torch.stack([mapx, mapy], dim=-1).unsqueeze(0).repeat(self.num_cams, 1, 1, 1) ##Initialize mats for all cameras self.cam_intrinsic = np.array([newcameramtx.copy() for _ in range(self.num_cams)] if self.undistort else [mtx.copy() for _ in range(self.num_cams)]) self.lidar2cam = np.array([LIDAR2CAM[name] for name in self.camera_names]) self.lidar2img = np.array([UNDISTORT_LIDAR2IMG[name] for name in self.camera_names] if self.undistort else [LIDAR2IMG[name] for name in self.camera_names]) def __call__(self, queue): """Call function to pad images, masks, semantic segmentation maps. Args: results (dict): Result dict from loading pipeline. Returns: dict: Updated result dict. """ #loading from queue imgs_list = np.stack([each['img'].data for each in queue], axis=0) temporal_len, num_cams, h, w, c = imgs_list.shape y_size, x_size = self.size y_scale, x_scale = y_size/h, x_size/w ## undistort imgs_list = torch.from_numpy(imgs_list).to(dtype=torch.get_default_dtype()).view(-1, h, w, c).permute(0, 3, 1, 2) if self.undistort: imgs_list = torch.nn.functional.grid_sample(imgs_list, self.map_grid, align_corners=False) imgs_list = self.resize_func(imgs_list).view(temporal_len, num_cams, c, y_size, x_size) ## depth label if self.use_depth: depth = torch.from_numpy(np.stack(queue[-1]['depth'])).to(dtype=torch.get_default_dtype()).view(-1,1,h,w) if self.undistort: depth = torch.nn.functional.grid_sample(depth, self.map_grid_depth, align_corners=False) queue[-1]['depth'] = self.resize_func(depth)[:,0,...] ## camera mat scale_factor = np.eye(4) scale_factor[0, 0] *= x_scale scale_factor[1, 1] *= y_scale for i in range(len(queue)): queue[i]["img_metas"].data['cam_intrinsic'] = self.cam_intrinsic queue[i]["img_metas"].data['lidar2cam'] = self.lidar2cam lidar2img = [scale_factor @ l2i for l2i in self.lidar2img] queue[i]["img_metas"].data['lidar2img'] = lidar2img queue[i]["img"] = imgs_list[i] queue[i]["img_metas"].data['img_shape'] = [imgs_list.shape[-2:]] * self.num_cams queue[i]["img_metas"].data['ori_shape'] = [imgs_list.shape[-2:]] * self.num_cams queue[i]["img_metas"].data['ida_mats'] = np.array([[[1,0,0,0], [0,1,0,0], [0,0,1,0], [0,0,0,1]]] * self.num_cams) return queue def __repr__(self): repr_str = self.__class__.__name__ repr_str += f'(size={self.size}, ' return repr_str @PIPELINES.register_module() class ImageTransformMulti(object): def __init__(self, aug, batch_size): self.transform = T.Compose([T.Normalize(mean=[0.485,0.456,0.406], std=[0.229,0.224,0.225])]) self.aug = aug self._batch_read_number = 0 self._batch_size = batch_size def __call__(self, queue): if self.aug: imgs_list = np.stack([each['img'].numpy().astype(np.uint8) for each in queue], axis=0).transpose((0, 1, 3, 4, 2)) temporal_len, num_cams, H, W, C = imgs_list.shape #temporal length x num_camera x H x W x C now_augmentor = augmenter(self._batch_read_number/self._batch_size).to_deterministic() ##Same ImgAug for all history frames and camera of one single sample new_imgs_list = np.stack([now_augmentor.augment_image(imgs_list[i][j]) for i in range(temporal_len) for j in range(num_cams)], axis=0).reshape(-1, H, W, C) new_imgs_list = self.transform(torch.from_numpy(new_imgs_list).permute(0, 3, 1, 2).to(dtype=torch.get_default_dtype()).div(255)).view(temporal_len, num_cams, C, H, W) for temporal_index in range(imgs_list.shape[0]): queue[temporal_index]["img"] = to_tensor(new_imgs_list[temporal_index]) self._batch_read_number += 1 else: for temporal_index in range(len(queue)): queue[temporal_index]["img"] = self.transform(queue[temporal_index]["img"].to(dtype=torch.get_default_dtype()).div(255)) return queue def __repr__(self): repr_str = self.__class__.__name__ repr_str += f'(aug={self.aug}, ' return repr_str def augmenter(image_iteration): iteration = image_iteration frequency_factor = min(0.05 + float(iteration)/600000.0, 1.0) color_factor = min(float(iteration)/3000000.0, 1.0) dropout_factor = 0.198667 + (0.03856658 - 0.198667) / (1 + (iteration / 600000) ** 1.863486) blur_factor = min(0.5 + (0.5*iteration/300000.0), 1.0) add_factor = 10 + 10*iteration/300000.0 multiply_factor_pos = 1 + (2.5*iteration/600000.0) multiply_factor_neg = 1 - (0.91 * iteration / 1500000.0) contrast_factor_pos = 1 + (0.5*iteration/1500000.0) contrast_factor_neg = 1 - (0.5 * iteration / 1500000.0) augmenter = iaa.Sequential([ iaa.Sometimes(frequency_factor, iaa.GaussianBlur((0, blur_factor))), # blur images with a sigma between 0 and 1.5 iaa.Sometimes(frequency_factor, iaa.AdditiveGaussianNoise(loc=0, scale=(0.0, dropout_factor), per_channel=color_factor)), # add gaussian noise to images iaa.Sometimes(frequency_factor, iaa.CoarseDropout((0.0, dropout_factor), size_percent=( 0.08, 0.2), per_channel=color_factor)), # randomly remove up to X% of the pixels iaa.Sometimes(frequency_factor, iaa.Dropout((0.0, dropout_factor), per_channel=color_factor)), # randomly remove up to X% of the pixels iaa.Sometimes(frequency_factor, iaa.Add((-add_factor, add_factor), per_channel=color_factor)), # change brightness of images (by -X to Y of original value) iaa.Sometimes(frequency_factor, iaa.Multiply((multiply_factor_neg, multiply_factor_pos), per_channel=color_factor)), # change brightness of images (X-Y% of original value) # iaa.Sometimes(frequency_factor, iaa.ContrastNormalization((contrast_factor_neg, contrast_factor_pos), # per_channel=color_factor)), iaa.Sometimes(frequency_factor, iaa.contrast.LinearContrast((contrast_factor_neg, contrast_factor_pos), per_channel=color_factor)), # improve or worsen the contrast iaa.Sometimes(frequency_factor, iaa.Grayscale((0.0, 1))), # put grayscale ], random_order=True # do all of the above in random order ) return augmenter ### From BEVDepth: https://github.com/Megvii-BaseDetection/BEVDepth @PIPELINES.register_module() class IDAImageTransform(object): def __init__(self, cfg, ida_aug_conf, is_train=False): self.ida_aug_conf = ida_aug_conf self.is_train = is_train self.size = cfg["img_size"] self.camera_names = cfg['camera_names'] self.resize_func = T.Resize(size=self.size) assert len(self.size)==2 self.undistort = cfg["undistort"] self.unreal_coord = cfg["unreal_coord"] self.use_depth = False if 'use_depth' not in cfg else cfg['use_depth'] self.use_seg = False if 'use_seg' not in cfg else cfg['use_seg'] ## Undistort mat mapx, mapy = cv2.initUndistortRectifyMap(mtx, dist, None, newcameramtx, (1600, 900), 5) mapx = (torch.from_numpy(mapx) - 800) / 800 mapy= (torch.from_numpy(mapy) - 450) / 450 self.num_cams = cfg["num_cams"] self.temporal_len = cfg["queue_length"] self.map_grid = torch.stack([mapx, mapy], dim=-1).unsqueeze(0).repeat(self.temporal_len*self.num_cams, 1, 1, 1) if self.use_depth or self.use_seg: self.map_grid_depth = torch.stack([mapx, mapy], dim=-1).unsqueeze(0).repeat(self.num_cams, 1, 1, 1) ##Initialize mats for all cameras self.cam_intrinsic = torch.from_numpy((np.stack([newcameramtx.copy() for _ in range(self.num_cams)], axis=0) if self.undistort else np.stack([mtx.copy() for _ in range(self.num_cams)], axis=0)).astype(np.float32)) self.lidar2cam = torch.from_numpy(np.stack([LIDAR2CAM[name] for name in self.camera_names], axis=0).astype(np.float32)) self.lidar2img = torch.from_numpy((np.stack([UNDISTORT_LIDAR2IMG[name] for name in self.camera_names], axis=0) if self.undistort else np.stack([LIDAR2IMG[name] for name in self.camera_names], axis=0)).astype(np.float32)) def sample_ida_augmentation(self): """Generate ida augmentation values based on ida_config.""" H, W = self.ida_aug_conf['H'], self.ida_aug_conf['W'] fH, fW = self.ida_aug_conf['final_dim'] if self.is_train: resize = np.random.uniform(*self.ida_aug_conf['resize_lim']) resize_dims = (int(W * resize), int(H * resize)) newW, newH = resize_dims crop_h = int( (1 - np.random.uniform(*self.ida_aug_conf['bot_pct_lim'])) * newH) - fH crop_w = int(np.random.uniform(0, max(0, newW - fW))) crop = (crop_w, crop_h, crop_w + fW, crop_h + fH) flip = False if self.ida_aug_conf['rand_flip'] and np.random.choice([0, 1]): flip = True else: resize = max(fH / H, fW / W) resize_dims = (int(W * resize), int(H * resize)) newW, newH = resize_dims crop_h = int( (1 - np.mean(self.ida_aug_conf['bot_pct_lim'])) * newH) - fH crop_w = int(max(0, newW - fW) / 2) crop = (crop_w, crop_h, crop_w + fW, crop_h + fH) flip = False return resize, resize_dims, crop, flip def __call__(self, queue): #loading from queue imgs_list = np.stack([each['img'].data for each in queue], axis=0) T, N, h, w, c = imgs_list.shape ## undistort imgs_list = torch.from_numpy(imgs_list).to(dtype=torch.get_default_dtype()).view(-1, h, w, c).permute(0, 3, 1, 2) if self.undistort: imgs_list = torch.nn.functional.grid_sample(imgs_list, self.map_grid, align_corners=False) imgs_list = imgs_list.view(T,N,c,h,w) ## depth label if self.use_depth: depth = torch.from_numpy(np.stack(queue[-1]['depth'])).to(dtype=torch.get_default_dtype()).view(-1,1,h,w) if self.undistort: depth = torch.nn.functional.grid_sample(depth, self.map_grid_depth, align_corners=False)[:,0] if self.use_seg: seg = torch.from_numpy(np.stack(queue[-1]['seg'])).to(dtype=torch.get_default_dtype()).view(-1,1,h,w) if self.undistort: seg = torch.nn.functional.grid_sample(seg, self.map_grid_depth, align_corners=False)[:,0] img_list_aug = [] ida_list = [] depth_list = [] seg_list = [] for cam_id in range(N): resize, resize_dims, crop, flip = self.sample_ida_augmentation() if self.use_depth: depth_aug = depth_transform( depth[cam_id], resize_dims, crop, flip) depth_list.append(depth_aug) if self.use_seg: seg_aug = depth_transform( seg[cam_id], resize_dims, crop, flip) seg_list.append(seg_aug) imgs, idas = [], [] for frame_id in range(T): img_aug, ida_mat = img_transform( imgs_list[frame_id][cam_id], resize=resize, resize_dims=resize_dims, crop=crop, flip=flip, rotate=0, ) imgs.append(img_aug) idas.append(ida_mat) imgs, idas = torch.stack(imgs), torch.stack(idas) img_list_aug.append(imgs) ida_list.append(idas) img_list_aug = torch.stack(img_list_aug).permute(1,0,2,3,4) ida_list = torch.stack(ida_list).permute(1,0,2,3) if self.use_depth: queue[-1]['depth'] = torch.stack(depth_list) if self.use_seg: queue[-1]['seg'] = torch.stack(seg_list) ## camera mat for i in range(len(queue)): # Save origin values, and they will be transformed in fpn_lss.py finally queue[i]["img_metas"].data['cam_intrinsic'] = self.cam_intrinsic queue[i]["img_metas"].data['lidar2cam'] = self.lidar2cam queue[i]["img_metas"].data['lidar2img'] = self.lidar2img queue[i]["img"] = img_list_aug[i] queue[i]["img_metas"].data['img_shape'] = [imgs_list.shape[-2:]] * self.num_cams queue[i]["img_metas"].data['ori_shape'] = [imgs_list.shape[-2:]] * self.num_cams queue[i]["img_metas"].data['ida_mats'] = ida_list[i] return queue def img_transform(img, resize, resize_dims, crop, flip, rotate=0): ida_rot = torch.eye(2) ida_tran = torch.zeros(2) (w,h) = resize_dims resize_func = T.Resize((h,w)) # adjust image img = resize_func(img) x0,y0,x1,y1 = crop img = img[..., y0:y1, x0:x1] if flip: img = torch.flip(img, dims=[-1]) # post-homography transformation ida_rot *= resize ida_tran -= torch.Tensor(crop[:2]) if flip: A = torch.Tensor([[-1, 0], [0, 1]]) b = torch.Tensor([crop[2] - crop[0], 0]) ida_rot = A.matmul(ida_rot) ida_tran = A.matmul(ida_tran) + b A = get_rot(rotate / 180 * np.pi) b = torch.Tensor([crop[2] - crop[0], crop[3] - crop[1]]) / 2 b = A.matmul(-b) + b ida_rot = A.matmul(ida_rot) ida_tran = A.matmul(ida_tran) + b ida_mat = ida_rot.new_zeros(4, 4) ida_mat[3, 3] = 1 ida_mat[2, 2] = 1 ida_mat[:2, :2] = ida_rot ida_mat[:2, 3] = ida_tran return img, ida_mat def get_rot(h): return torch.Tensor([ [np.cos(h), np.sin(h)], [-np.sin(h), np.cos(h)], ]) def depth_transform(depth, resize_dims, crop, flip): (w,h) = resize_dims resize_func = T.Resize((h,w)) # adjust image depth = resize_func(depth.unsqueeze(0)) x0,y0,x1,y1 = crop depth = depth[..., y0:y1, x0:x1] if flip: depth = torch.flip(depth, dims=[-1]) return depth[0] ================================================ FILE: open_loop_training/code/datasets/samplers/__init__.py ================================================ from .group_sampler import DistributedGroupSampler from .distributed_sampler import DistributedSampler from .sampler import SAMPLER, build_sampler ================================================ FILE: open_loop_training/code/datasets/samplers/distributed_sampler.py ================================================ import math import torch from torch.utils.data import DistributedSampler as _DistributedSampler from .sampler import SAMPLER @SAMPLER.register_module() class DistributedSampler(_DistributedSampler): def __init__(self, dataset=None, num_replicas=None, rank=None, shuffle=True, seed=0): super().__init__( dataset, num_replicas=num_replicas, rank=rank, shuffle=shuffle) # for the compatibility from PyTorch 1.3+ self.seed = seed if seed is not None else 0 def __iter__(self): # deterministically shuffle based on epoch if self.shuffle: assert False else: indices = torch.arange(len(self.dataset)).tolist() # add extra samples to make it evenly divisible # in case that indices is shorter than half of total_size indices = (indices * math.ceil(self.total_size / len(indices)))[:self.total_size] assert len(indices) == self.total_size # subsample per_replicas = self.total_size//self.num_replicas # indices = indices[self.rank:self.total_size:self.num_replicas] indices = indices[self.rank*per_replicas:(self.rank+1)*per_replicas] assert len(indices) == self.num_samples return iter(indices) ================================================ FILE: open_loop_training/code/datasets/samplers/group_sampler.py ================================================ # Copyright (c) OpenMMLab. All rights reserved. import math import numpy as np import torch from mmcv.runner import get_dist_info from torch.utils.data import Sampler from .sampler import SAMPLER import random @SAMPLER.register_module() class DistributedGroupSampler(Sampler): """Sampler that restricts data loading to a subset of the dataset. It is especially useful in conjunction with :class:`torch.nn.parallel.DistributedDataParallel`. In such case, each process can pass a DistributedSampler instance as a DataLoader sampler, and load a subset of the original dataset that is exclusive to it. .. note:: Dataset is assumed to be of constant size. Arguments: dataset: Dataset used for sampling. num_replicas (optional): Number of processes participating in distributed training. rank (optional): Rank of the current process within num_replicas. seed (int, optional): random seed used to shuffle the sampler if ``shuffle=True``. This number should be identical across all processes in the distributed group. Default: 0. """ def __init__(self, dataset, samples_per_gpu=1, num_replicas=None, rank=None, seed=0): _rank, _num_replicas = get_dist_info() if num_replicas is None: num_replicas = _num_replicas if rank is None: rank = _rank self.dataset = dataset self.samples_per_gpu = samples_per_gpu self.num_replicas = num_replicas self.rank = rank self.epoch = 0 self.seed = seed if seed is not None else 0 assert hasattr(self.dataset, 'flag') self.flag = self.dataset.flag self.group_sizes = np.bincount(self.flag) self.num_samples = 0 for i, j in enumerate(self.group_sizes): self.num_samples += int( math.ceil(self.group_sizes[i] * 1.0 / self.samples_per_gpu / self.num_replicas)) * self.samples_per_gpu self.total_size = self.num_samples * self.num_replicas def __iter__(self): # deterministically shuffle based on epoch g = torch.Generator() g.manual_seed(self.epoch + self.seed) indices = [] for i, size in enumerate(self.group_sizes): if size > 0: indice = np.where(self.flag == i)[0] assert len(indice) == size indice = indice[list( torch.randperm(int(size), generator=g).numpy())].tolist() extra = int( math.ceil( size * 1.0 / self.samples_per_gpu / self.num_replicas) ) * self.samples_per_gpu * self.num_replicas - len(indice) # pad indice tmp = indice.copy() for _ in range(extra // size): indice.extend(tmp) indice.extend(tmp[:extra % size]) indices.extend(indice) assert len(indices) == self.total_size indices = [ indices[j] for i in list( torch.randperm( len(indices) // self.samples_per_gpu, generator=g)) for j in range(i * self.samples_per_gpu, (i + 1) * self.samples_per_gpu) ] # subsample offset = self.num_samples * self.rank indices = indices[offset:offset + self.num_samples] assert len(indices) == self.num_samples return iter(indices) def __len__(self): return self.num_samples def set_epoch(self, epoch): self.epoch = epoch ================================================ FILE: open_loop_training/code/datasets/samplers/sampler.py ================================================ from mmcv.utils.registry import Registry, build_from_cfg SAMPLER = Registry('sampler') def build_sampler(cfg, default_args): return build_from_cfg(cfg, SAMPLER, default_args) ================================================ FILE: open_loop_training/code/encoder_decoder_framework.py ================================================ from collections import deque, OrderedDict from distutils.command.config import config import cv2 import numpy as np import matplotlib matplotlib.use('AGG') import matplotlib.pyplot as plt import torch from torch import nn import torch.nn.functional as F import torch.distributed as dist from torchvision import transforms as T from mmcv.runner import BaseModule from mmdet.models import DETECTORS import mmcls.models from mmdet3d.models import builder from mmcv.runner import force_fp32, auto_fp16 from .utils import PIDController, FocalLoss, set_dropout_zero, init_weights, SEBasicBlock @DETECTORS.register_module() class EncoderDecoder(BaseModule): def __init__(self, img_encoder, decoder, lidar_encoder=None, num_cams = 4, use_depth=False, use_seg=False, downsample_factor=16, seg_downsample_factor=2, train_cfg=None, test_cfg=None, ): super().__init__() self.config = train_cfg self.fp16_enabled = False self.num_cams = num_cams self.use_depth = False if 'use_depth' not in train_cfg else train_cfg['use_depth'] self.use_seg = False if 'use_seg' not in train_cfg else train_cfg['use_seg'] self.downsample_factor = downsample_factor self.seg_downsample_factor = seg_downsample_factor self.turn_controller = PIDController(K_P=self.config['turn_KP'], K_I=self.config['turn_KI'], K_D=self.config['turn_KD'], n=self.config['turn_n']) self.speed_controller = PIDController(K_P=self.config['speed_KP'], K_I=self.config['speed_KI'], K_D=self.config['speed_KD'], n=self.config['speed_n']) ## Encoder self.img_encoder = builder.build_backbone(img_encoder) self.depth_resize = None self.dbound = self.img_encoder.d_bound self.depth_channels = int((self.dbound[1] - self.dbound[0]) / self.dbound[2]) self.seg_loss_func = FocalLoss() self.lidar_encoder = builder.build_backbone(lidar_encoder) self.act = nn.ReLU self.build_fusion_and_flatten_network_for_BEV() self.measurements_encoder = nn.Sequential( nn.Linear(1+2+6, 128), self.act(), nn.Linear(128, 128), self.act(), ) nn.init.xavier_normal_(self.measurements_encoder[0].weight) nn.init.constant_(self.measurements_encoder[0].bias, 0) nn.init.xavier_normal_(self.measurements_encoder[2].weight) nn.init.constant_(self.measurements_encoder[2].bias, 0) ## Decoder self.decoder= builder.build_head(decoder) self.max_epoch = 60 if "total_epochs" in self.config: self.max_epoch = self.config["total_epochs"] def set_epoch(self, epoch): self.epoch = epoch @auto_fp16() def build_fusion_and_flatten_network_for_BEV(self): ### BEV Fusion Network self.norm = nn.BatchNorm2d self.inplace_act = self.act() self.conv_cam = nn.Sequential( nn.Conv2d(256, 256, kernel_size=3, padding=1, bias=False), self.norm(256), self.act(), nn.Conv2d(256, 256, kernel_size=3, padding=1, bias=False), self.norm(256), ) self.conv_cam.apply(init_weights) self.conv_lidar = nn.Sequential( nn.Conv2d(256*2, 256, kernel_size=3, padding=1, bias=False, stride=2), self.norm(256), self.act(), nn.Conv2d(256, 256, kernel_size=3, padding=1, bias=False, stride=2), self.norm(256), self.act(), ) self.conv_lidar.apply(init_weights) self.conv_fusion = nn.Sequential( nn.Conv2d(256*2, 256, kernel_size=3, padding=1, bias=False), self.norm(256), self.act(), nn.Conv2d(256, 256, kernel_size=3, padding=1, bias=False), self.norm(256), ) self.conv_fusion.apply(init_weights) ### Transform Raw BEV feature to 1D feature map ## The dimension of middle BEV feature map follows Roach to enable feature distillation self._256_to_32 = nn.Conv2d(256, 32, kernel_size=3, padding=1) self._256_to_32.apply(init_weights) self.MLP21 = SEBasicBlock(32, self.act) ## MLP for the 21x21 BEV feature map self.MLP10 = SEBasicBlock(64, self.act) ## MLP for the 10x10 BEV feature map self.MLP4 = SEBasicBlock(128, self.act) ## MLP for the 4x4 BEV feature map self.MLP2 = SEBasicBlock(256, self.act) ## MLP for the 2x2 BEV feature map self.MLP21.apply(init_weights) self.MLP10.apply(init_weights) self.MLP4.apply(init_weights) self.MLP2.apply(init_weights) self.conv21_10 = nn.Conv2d(32, 64, kernel_size=3, stride=2) self.conv10_4 = nn.Conv2d(64, 128, kernel_size=3, stride=2) self.conv4_2 = nn.Conv2d(128, 256, kernel_size=3, stride=1) self.conv21_10.apply(init_weights) self.conv10_4.apply(init_weights) self.conv4_2.apply(init_weights) self.output_fc = nn.Sequential( nn.Linear(1024, 512), self.act(), nn.BatchNorm1d(512), nn.Linear(512, 256), self.act() ) self.output_fc.apply(init_weights) def train_step(self, data, optimizer): losses = self.forward_train(data) loss, log_vars = self._parse_losses(losses) outputs = dict( loss=loss, log_vars=log_vars, num_samples=data['img'].shape[0]) return outputs @force_fp32() def forward_train(self, batch): target_point = batch['target_point'].to(dtype=torch.float32) command = batch['target_command'] speed = batch['speed'].to(dtype=torch.float32).view(-1,1) / 12. state = [speed, target_point, command, batch['target_command_raw']] # extract all modal features points = batch['points'] if 'points' in batch else None cam_feat, lidar_feat, measurement_feat = self.extract_sensor_feat( img=batch['img'], state=state, img_metas=batch['img_metas'], points=points) flattend_BEV_feat, fusion_feats, mid_BEV_feature, mid_lidar_feat = self.get_fusion_feat(cam_feat, lidar_feat) teacher_forcing_input = {} for teacher_key in ["waypoints", "action_sigma", "action_mu", "future_action_sigma", "future_action_mu"]: teacher_forcing_input[teacher_key] = batch[teacher_key] ## Decoder pred = self.decoder(flattend_BEV_feat, fusion_feats, measurement_feat, target_point, self, teacher_forcing_input, [cam_feat["lidar2img"], cam_feat["ida_mat"], cam_feat["fpn_feats"], mid_lidar_feat]) loss_dict = self.decoder.loss(batch, pred, mid_BEV_feature) ## seg supervision if self.use_seg: seg_gt = self.get_downsampled_gt_seg(batch['seg']) seg_pred = cam_feat['seg'] seg_loss = self.seg_loss_func(seg_pred, seg_gt) loss_dict['seg_loss'] = seg_loss * 10 ## depth supervision if self.use_depth: depth_gt = batch['depth'] depth_gt = self.get_downsampled_gt_depth(depth_gt) depth_pred = cam_feat['depth'].permute(0, 2, 3, 1).contiguous().view( -1, self.depth_channels) fg_mask = torch.max(depth_gt, dim=1).values > 0.0 depth_loss = F.binary_cross_entropy_with_logits( depth_pred[fg_mask], depth_gt[fg_mask], reduction='none', ).sum() / max(1.0, fg_mask.sum()) loss_dict['depth_loss'] = depth_loss return loss_dict ## For close-loop evaluation def forward_inference(self, batch): self.epoch = 10000 target_point = batch['target_point'].to(dtype=torch.float32) command = batch['target_command'] speed = batch['speed'].to(dtype=torch.float32).view(-1,1) / 12. state = [speed, target_point, command, batch['target_command_raw']] # extract all modal features points = batch['points'] if 'points' in batch else None cam_feat, lidar_feat, measurement_feat = self.extract_sensor_feat( img=batch['img'], state=state, img_metas=batch['img_metas'], points=points) flattend_BEV_feat, fusion_feats, mid_feature, mid_lidar_feat = self.get_fusion_feat(cam_feat, lidar_feat) teacher_forcing_data = None pred = self.decoder(flattend_BEV_feat, fusion_feats, measurement_feat, target_point, self, teacher_forcing_data, [cam_feat["lidar2img"], cam_feat["ida_mat"], cam_feat["fpn_feats"], mid_lidar_feat]) return pred @auto_fp16() def get_fusion_feat(self, cam_feat, lidar_feat,): lidar_feat_with_high_resolution = lidar_feat[0].clone() #fusion cam_feats_reduce = self.inplace_act(self.conv_cam(cam_feat['bev']) + cam_feat['bev']) # Residual Connection if self.lidar_encoder is not None: pts_feats_reduce = self.conv_lidar(lidar_feat[0]) bev_feats = self.inplace_act(self.conv_fusion(torch.cat([cam_feats_reduce, pts_feats_reduce], dim=1)) + cam_feats_reduce + pts_feats_reduce) # Residual Connection Bx256x21x21 else: bev_feats = cam_feats_reduce # Bx256x21x21 mid_feature = [None, None] #Currently no feature for 8x94x94 16x45x45 feats32_21_21 = self.MLP21(self.inplace_act(self._256_to_32(bev_feats))) bev_feats = feats32_21_21 mid_feature.append(feats32_21_21) feats64_10_10 = self.MLP10(self.inplace_act(self.conv21_10(feats32_21_21))) mid_feature.append(feats64_10_10) feats128_4_4 = self.MLP4(self.inplace_act(self.conv10_4(feats64_10_10))) mid_feature.append(feats128_4_4) feats256_2_2 = self.MLP2(self.inplace_act(self.conv4_2((feats128_4_4)))) mid_feature.append(feats256_2_2) flattend_BEV_feat = self.output_fc(feats256_2_2.flatten(start_dim=1)) # Bx256 return flattend_BEV_feat, bev_feats, mid_feature, lidar_feat_with_high_resolution @auto_fp16() def extract_sensor_feat(self, img, state, img_metas, points, is_train=True): # extract camera feature cam_feat = self.img_encoder(img=img, img_metas=img_metas, is_return_depth=self.use_depth and is_train) cam_feat['bev'] = torch.rot90(torch.flip(cam_feat['bev'],dims=[2]), 1, dims=[2,3]) ### Match with Roach BEV state = torch.cat(state[:3], dim=-1) measurement_feat = self.measurements_encoder(state) lidar_feat = self.lidar_encoder(points[:, -1, ...]) for i in range(len(lidar_feat)): lidar_feat[i] = torch.rot90(torch.flip(lidar_feat[i],dims=[2]), 1, dims=[2,3]) ### Match with Roach BEV ## Visualization of BEV feature if False: self.plot(cam_feat['bev'], lidar_feat[0], img_metas[0]) return cam_feat, lidar_feat, measurement_feat def plot(self, cam_feats, fusion_feats, img_metas): def get_plot(arr): arr2 = arr.cpu().detach().numpy() return np.max(arr2,axis=0) for i in [0]: plt.clf() plt.subplot(2,1,1) plt.imshow(get_plot(cam_feats[i]))#[::-1]) plt.title('cam feature') plt.subplot(2,1,2) plt.imshow(get_plot(fusion_feats[i]))#[::-1]) plt.title('lidar feature') plt.suptitle('x=[-8.0, 30.4], y=[-19.2, 19.2]') plt.savefig('cam_fusion_'+str(i)+'.png') @force_fp32() def process_action(self, pred, command, speed, target_point): action = self._get_action_beta(pred['mu_branches'][:, -1, :].view(1,2), pred['sigma_branches'][:, -1, :].view(1,2)) acc, steer = action.cpu().numpy()[0].astype(np.float64) if acc >= 0.0: throttle = acc brake = 0.0 else: throttle = 0.0 brake = np.abs(acc) throttle = np.clip(throttle, 0, 1) steer = np.clip(steer, -1, 1) brake = np.clip(brake, 0, 1) metadata = { 'speed': float(speed.cpu().numpy().astype(np.float64)), 'steer': float(steer), 'throttle': float(throttle), 'brake': float(brake), 'command': command, 'target_point': target_point, } return steer, throttle, brake, metadata @force_fp32() def _get_action_beta(self, alpha, beta): x = torch.zeros_like(alpha) x[:, 1] += 0.5 mask1 = (alpha > 1) & (beta > 1) x[mask1] = (alpha[mask1]-1)/(alpha[mask1]+beta[mask1]-2) mask2 = (alpha <= 1) & (beta > 1) x[mask2] = 0.0 mask3 = (alpha > 1) & (beta <= 1) x[mask3] = 1.0 # mean mask4 = (alpha <= 1) & (beta <= 1) x[mask4] = alpha[mask4]/torch.clamp((alpha[mask4]+beta[mask4]), min=1e-5) x = x * 2 - 1 return x ## Copy from TCP ## Modified by Xiaosong Jia @force_fp32() def control_pid(self, waypoints, velocity, target, stuck_desired_speed=-1): ''' Predicts vehicle control with a PID controller. Args: waypoints (tensor): output of self.plan() velocity (tensor): speedometer input ''' assert(waypoints.size(0)==1) waypoints = waypoints[0].data.cpu().numpy() saved_waypoints = waypoints.copy() saved_target = target.copy() waypoints = waypoints[:, ::-1] target = target[::-1] # iterate over vectors between predicted waypoints num_pairs = len(waypoints) - 1 best_norm = 1e5 desired_speed = 0 aim = waypoints[0] for i in range(num_pairs): # magnitude of vectors, used for speed desired_speed += np.linalg.norm( waypoints[i+1] - waypoints[i]) * 2.0 / num_pairs # norm of vector midpoints, used for steering norm = np.linalg.norm((waypoints[i+1] + waypoints[i]) / 2.0) if abs(self.config['aim_dist']-best_norm) > abs(self.config['aim_dist']-norm): aim = waypoints[i] best_norm = norm desired_speed = desired_speed.astype(np.float64) if stuck_desired_speed > 0: desired_speed = stuck_desired_speed aim_last = waypoints[-1] - waypoints[-2] angle = np.degrees(np.pi / 2 - np.arctan2(aim[1], aim[0])) / 90 angle_last = np.degrees(np.pi / 2 - np.arctan2(aim_last[1], aim_last[0])) / 90 angle_target = np.degrees(np.pi / 2 - np.arctan2(target[1], target[0])) / 90 # choice of point to aim for steering, removing outlier predictions # use target point if it has a smaller angle or if error is large # predicted point otherwise # (reduces noise in eg. straight roads, helps with sudden turn commands) use_target_to_aim = np.abs(angle_target) < np.abs(angle) #angle_thresh use_target_to_aim = use_target_to_aim or (np.abs(angle_target-angle_last) > self.config['angle_thresh'] and target[1] < self.config['dist_thresh']) if use_target_to_aim: angle_final = angle_target else: angle_final = angle angle_final = angle_final.astype(np.float64) speed = velocity[0].data.cpu().numpy() if (speed < 0.01): angle_final = 0.0 # When we don't move we don't want the angle error to accumulate in the integral steer = self.turn_controller.step(angle_final) steer = np.clip(steer, -1.0, 1.0) brake = desired_speed < self.config['brake_speed'] or (speed / desired_speed) > self.config['brake_ratio'] delta = np.clip(desired_speed - speed, 0.0, self.config['clip_delta']) throttle = self.speed_controller.step(delta) throttle = np.clip(throttle, 0.0, 1.0)#self.config['max_throttle']) throttle = throttle if not brake else 0.0 metadata = { 'speed': float(speed.astype(np.float64)), 'steer': float(steer), 'throttle': float(throttle), 'brake': float(brake), 'wp_4': tuple(saved_waypoints[3].astype(np.float64)), 'wp_3': tuple(saved_waypoints[2].astype(np.float64)), 'wp_2': tuple(saved_waypoints[1].astype(np.float64)), 'wp_1': tuple(saved_waypoints[0].astype(np.float64)), 'aim': tuple(aim.astype(np.float64)), 'target': tuple(saved_target.astype(np.float64)), 'desired_speed': float(desired_speed), 'angle': float(angle.astype(np.float64)), 'angle_last': float(angle_last.astype(np.float64)), 'angle_target': float(angle_target.astype(np.float64)), 'angle_final': float(angle_final), 'delta': float(delta.astype(np.float64)), } return steer, throttle, brake, metadata @force_fp32() def forward(self, is_eval=True, **kwargs): """Calls either forward_train or forward_test depending on whether return_loss=True. Note this setting will change the expected inputs. When `return_loss=True`, img and img_metas are single-nested (i.e. torch.Tensor and list[dict]), and when `resturn_loss=False`, img and img_metas should be double nested (i.e. list[torch.Tensor], list[list[dict]]), with the outer list indicating test time augmentations. """ losses = self.forward_train(kwargs) loss, log_vars = self._parse_losses(losses) outputs = dict( loss=loss, log_vars=log_vars, num_samples=kwargs['img'].shape[0]) return outputs @force_fp32() def _parse_losses(self, losses): """Parse the raw outputs (losses) of the network. Args: losses (dict): Raw output of the network, which usually contain losses and other necessary infomation. Returns: tuple[Tensor, dict]: (loss, log_vars), loss is the loss tensor \ which may be a weighted sum of all losses, log_vars contains \ all the variables to be sent to the logger. """ log_vars = OrderedDict() for loss_name, loss_value in losses.items(): if isinstance(loss_value, torch.Tensor): log_vars[loss_name] = loss_value.mean() elif isinstance(loss_value, list): log_vars[loss_name] = sum(_loss.mean() for _loss in loss_value) else: raise TypeError( f'{loss_name} is not a tensor or list of tensors') loss = sum(_value for _key, _value in log_vars.items() if 'loss' in _key) log_vars['loss'] = loss for loss_name, loss_value in log_vars.items(): # reduce loss when distributed training if dist.is_available() and dist.is_initialized(): loss_value = loss_value.data.clone() dist.all_reduce(loss_value.div_(dist.get_world_size())) log_vars[loss_name] = loss_value.item() return loss, log_vars @force_fp32() def get_downsampled_gt_depth(self, gt_depths, min_pooling=True): """ Input: gt_depths: [B, N, H, W] Output: gt_depths: [B*N*h*w, d] """ B, N, H, W = gt_depths.shape if min_pooling: gt_depths = gt_depths.view( B * N, H // self.downsample_factor, self.downsample_factor, W // self.downsample_factor, self.downsample_factor, 1, ) gt_depths = gt_depths.permute(0, 1, 3, 5, 2, 4).contiguous() gt_depths = gt_depths.view( -1, self.downsample_factor * self.downsample_factor) gt_depths_tmp = torch.where(gt_depths == 0.0, 1e5 * torch.ones_like(gt_depths), gt_depths) gt_depths = torch.min(gt_depths_tmp, dim=-1).values gt_depths = gt_depths.view(B * N, H // self.downsample_factor, W // self.downsample_factor) else: # just use nearest sampling if self.depth_resize is None: self.depth_resize = T.Resize((H//self.downsample_factor,W//self.downsample_factor), interpolation=T.InterpolationMode.NEAREST) gt_depths = gt_depths.view(B*N, H, W) gt_depths = self.depth_resize(gt_depths) gt_depths = (gt_depths - (self.dbound[0] - self.dbound[2])) / self.dbound[2] gt_depths = torch.where( (gt_depths < self.depth_channels + 1) & (gt_depths >= 0.0), gt_depths, torch.zeros_like(gt_depths)) gt_depths = F.one_hot(gt_depths.long(), num_classes=self.depth_channels + 1).view( -1, self.depth_channels + 1)[:, 1:] return gt_depths.float() @force_fp32() def get_downsampled_gt_seg(self, gt_seg): B, N, H, W = gt_seg.shape if self.depth_resize is None: self.depth_resize = T.Resize((H//self.seg_downsample_factor,W//self.seg_downsample_factor), interpolation=T.InterpolationMode.NEAREST) gt_seg = gt_seg.view(B*N, H, W) gt_seg = self.depth_resize(gt_seg) return gt_seg.long() ================================================ FILE: open_loop_training/code/model_code/backbones/__init__.py ================================================ from .lidarnet import LidarNet, SparseEncoder_fp32 from .lss import LSS, PAFPN_fp32 __all__ = ['LidarNet', 'LSS', "SparseEncoder_fp32", "PAFPN_fp32"] ================================================ FILE: open_loop_training/code/model_code/backbones/lidarnet.py ================================================ import copy import numpy as np import torch import torch.nn as nn import torch.nn.functional as F from torch.distributions import Beta from mmcv.runner import BaseModule from mmcv.runner import force_fp32, auto_fp16 from mmdet.models import BACKBONES from mmdet.core import (multi_apply, multi_apply, reduce_mean) from mmdet3d.models.detectors.mvx_two_stage import MVXTwoStageDetector from mmdet3d.models.builder import MIDDLE_ENCODERS from mmdet3d.models.middle_encoders.sparse_encoder import SparseEncoder from mmdet3d.ops.spconv import IS_SPCONV2_AVAILABLE if IS_SPCONV2_AVAILABLE: from spconv.pytorch import SparseConvTensor else: from mmcv.ops import SparseConvTensor #To avoid strange FP16 inf norm bug @MIDDLE_ENCODERS.register_module() class SparseEncoder_fp32(SparseEncoder): @force_fp32() def forward(self, voxel_features, coors, batch_size): """Forward of SparseEncoder. Args: voxel_features (torch.Tensor): Voxel features in shape (N, C). coors (torch.Tensor): Coordinates in shape (N, 4), the columns in the order of (batch_idx, z_idx, y_idx, x_idx). batch_size (int): Batch size. Returns: dict: Backbone features. """ coors = coors.int() input_sp_tensor = SparseConvTensor(voxel_features, coors, self.sparse_shape, batch_size) x = self.conv_input(input_sp_tensor) encode_features = [] for encoder_layer in self.encoder_layers: x = encoder_layer(x) encode_features.append(x) # for detection head # [200, 176, 5] -> [200, 176, 2] out = self.conv_out(encode_features[-1]) spatial_features = out.dense() N, C, D, H, W = spatial_features.shape spatial_features = spatial_features.view(N, C * D, H, W) return spatial_features @BACKBONES.register_module() class LidarNet(MVXTwoStageDetector): def __init__(self, bev_h=None, bev_w=None, pts_voxel_layer=None, pts_voxel_encoder=None, pts_middle_encoder=None, pts_fusion_layer=None, pts_backbone=None, pts_neck=None, pts_bbox_head=None, train_cfg=None, test_cfg=None, ): self.bev_h = bev_h self.bev_w = bev_w super(LidarNet, self).__init__(pts_voxel_layer, pts_voxel_encoder, pts_middle_encoder, pts_fusion_layer, None, pts_backbone, None, pts_neck, pts_bbox_head, None, None, train_cfg, test_cfg, None) self.fp16_enabled = False @auto_fp16() def forward(self, pts): voxels, num_points, coors = self.voxelize(pts) voxel_features = self.pts_voxel_encoder(voxels, num_points, coors) batch_size = coors[-1, 0] + 1 x = self.pts_middle_encoder(voxel_features, coors, batch_size) if self.with_pts_backbone: x = self.pts_backbone(x) if self.with_pts_neck: x = self.pts_neck(x) return x ================================================ FILE: open_loop_training/code/model_code/backbones/lss.py ================================================ ## Copyright (c) Megvii Inc. All rights reserved. ## From BEVDepth ## Modified by Xiaosong Jia import torch import torch.nn.functional as F from mmcv.runner import BaseModule from mmdet.models import BACKBONES from mmcv.cnn import build_conv_layer from mmdet3d.models import build_neck from mmdet.models import build_backbone from mmdet.models.backbones.resnet import BasicBlock from torch import nn import numpy as np from ops.voxel_pooling import voxel_pooling from mmcv.runner import force_fp32, auto_fp16 __all__ = ['LSS'] class _ASPPModule(nn.Module): def __init__(self, inplanes, planes, kernel_size, padding, dilation, BatchNorm): super(_ASPPModule, self).__init__() self.atrous_conv = nn.Conv2d(inplanes, planes, kernel_size=kernel_size, stride=1, padding=padding, dilation=dilation, bias=False) self.bn = BatchNorm(planes) self.relu = nn.ReLU() self._init_weight() def forward(self, x): x = self.atrous_conv(x) x = self.bn(x) return self.relu(x) def _init_weight(self): for m in self.modules(): if isinstance(m, nn.Conv2d): torch.nn.init.kaiming_normal_(m.weight) elif isinstance(m, nn.BatchNorm2d): m.weight.data.fill_(1) m.bias.data.zero_() class ASPP(nn.Module): def __init__(self, inplanes, mid_channels=256, BatchNorm=nn.BatchNorm2d): super(ASPP, self).__init__() dilations = [1, 6, 12, 18] self.aspp1 = _ASPPModule(inplanes, mid_channels, 1, padding=0, dilation=dilations[0], BatchNorm=BatchNorm) self.aspp2 = _ASPPModule(inplanes, mid_channels, 3, padding=dilations[1], dilation=dilations[1], BatchNorm=BatchNorm) self.aspp3 = _ASPPModule(inplanes, mid_channels, 3, padding=dilations[2], dilation=dilations[2], BatchNorm=BatchNorm) self.aspp4 = _ASPPModule(inplanes, mid_channels, 3, padding=dilations[3], dilation=dilations[3], BatchNorm=BatchNorm) self.global_avg_pool = nn.Sequential( nn.AdaptiveAvgPool2d((1, 1)), nn.Conv2d(inplanes, mid_channels, 1, stride=1, bias=False), BatchNorm(mid_channels), nn.ReLU(), ) self.conv1 = nn.Conv2d(int(mid_channels * 5), mid_channels, 1, bias=False) self.bn1 = BatchNorm(mid_channels) self.relu = nn.ReLU() self.dropout = nn.Dropout(0.5) self._init_weight() def forward(self, x): x1 = self.aspp1(x) x2 = self.aspp2(x) x3 = self.aspp3(x) x4 = self.aspp4(x) x5 = self.global_avg_pool(x) x5 = F.interpolate(x5, size=x4.size()[2:], mode='bilinear', align_corners=True) x = torch.cat((x1, x2, x3, x4, x5), dim=1) x = self.conv1(x) x = self.bn1(x) x = self.relu(x) return self.dropout(x) def _init_weight(self): for m in self.modules(): if isinstance(m, nn.Conv2d): torch.nn.init.kaiming_normal_(m.weight) elif isinstance(m, nn.BatchNorm2d): m.weight.data.fill_(1) m.bias.data.zero_() class Mlp(nn.Module): def __init__(self, in_features, hidden_features=None, out_features=None, act_layer=nn.ReLU, drop=0.0): super().__init__() out_features = out_features or in_features hidden_features = hidden_features or in_features self.fc1 = nn.Linear(in_features, hidden_features) self.act = act_layer() self.drop1 = nn.Dropout(drop) self.fc2 = nn.Linear(hidden_features, out_features) self.drop2 = nn.Dropout(drop) def forward(self, x): x = self.fc1(x) x = self.act(x) x = self.drop1(x) x = self.fc2(x) x = self.drop2(x) return x class SELayer(nn.Module): def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid): super().__init__() self.conv_reduce = nn.Conv2d(channels, channels, 1, bias=True) self.act1 = act_layer() self.conv_expand = nn.Conv2d(channels, channels, 1, bias=True) self.gate = gate_layer() def forward(self, x, x_se): x_se = self.conv_reduce(x_se) x_se = self.act1(x_se) x_se = self.conv_expand(x_se) return x * self.gate(x_se) class DepthNet(nn.Module): def __init__(self, in_channels, mid_channels, context_channels, depth_channels): super(DepthNet, self).__init__() self.reduce_conv = nn.Sequential( nn.Conv2d(in_channels, mid_channels, kernel_size=3, stride=1, padding=1), nn.BatchNorm2d(mid_channels), nn.ReLU(inplace=True), ) self.context_conv = nn.Conv2d(mid_channels, context_channels, kernel_size=1, stride=1, padding=0) self.bn = nn.BatchNorm1d(22) self.depth_mlp = Mlp(22, mid_channels, mid_channels) self.depth_se = SELayer(mid_channels) # NOTE: add camera-aware self.context_mlp = Mlp(22, mid_channels, mid_channels) self.context_se = SELayer(mid_channels) # NOTE: add camera-aware self.depth_conv = nn.Sequential( BasicBlock(mid_channels, mid_channels), BasicBlock(mid_channels, mid_channels), BasicBlock(mid_channels, mid_channels), ASPP(mid_channels, mid_channels), build_conv_layer(cfg=dict( type='DCN', in_channels=mid_channels, out_channels=mid_channels, kernel_size=3, padding=1, groups=4, im2col_step=128, )), nn.Conv2d(mid_channels, depth_channels, kernel_size=1, stride=1, padding=0), ) def forward(self, x, mats_dict): # mats_dict B x T x N intrins = mats_dict['intrin_mats'][:, -1:, ..., :3, :3] batch_size = intrins.shape[0] num_cams = intrins.shape[2] ida = mats_dict['ida_mats'][:, -1:, ...] sensor2ego = mats_dict['sensor2ego_mats'][:, -1:, ..., :3, :] mlp_input = torch.cat( [ torch.stack( [ intrins[:, 0:1, ..., 0, 0], intrins[:, 0:1, ..., 1, 1], intrins[:, 0:1, ..., 0, 2], intrins[:, 0:1, ..., 1, 2], ida[:, 0:1, ..., 0, 0], ida[:, 0:1, ..., 0, 1], ida[:, 0:1, ..., 0, 3], ida[:, 0:1, ..., 1, 0], ida[:, 0:1, ..., 1, 1], ida[:, 0:1, ..., 1, 3], ], dim=-1, ), sensor2ego.view(batch_size, 1, num_cams, -1), ], -1, ) mlp_input = self.bn(mlp_input.reshape(-1, mlp_input.shape[-1])) x = self.reduce_conv(x) context_se = self.context_mlp(mlp_input)[..., None, None] context = self.context_se(x, context_se) context = self.context_conv(context) depth_se = self.depth_mlp(mlp_input)[..., None, None] depth = self.depth_se(x, depth_se) depth = self.depth_conv(depth) return torch.cat([depth, context], dim=1) class UnetLayer(nn.Module): def __init__(self, in_channels, middle_channels, out_channels): super(UnetLayer, self).__init__() self.up = nn.ConvTranspose2d(in_channels, out_channels, kernel_size=2, stride=2) self.conv_relu = nn.Sequential( nn.Conv2d(middle_channels, out_channels, kernel_size=3, padding=1), nn.ReLU(inplace=True), ) self.fp16_enabled = False @force_fp32() def forward(self, x1, x2): x1 = self.up(x1) x1 = torch.cat((x1, x2), dim=1) x1 = self.conv_relu(x1) return x1 class UNet(nn.Module): def __init__(self, n_class, fpn_in_channels): super().__init__() self.unet_layer4 = UnetLayer(fpn_in_channels[3], 256+fpn_in_channels[2], 256) self.unet_layer3 = UnetLayer(256, 256+fpn_in_channels[1], 256) self.unet_layer2 = UnetLayer(256, 128+fpn_in_channels[0], 128) self.unet_layer0 = nn.Sequential( nn.Upsample(scale_factor=2, mode='bilinear', align_corners=True), nn.Conv2d(128, 64, kernel_size=3, padding=1, bias=False), nn.ReLU(inplace=True), nn.Conv2d(64, 64, kernel_size=3, padding=1, bias=False) ) self.conv_last = nn.Conv2d(64, n_class, 1) self.fp16_enabled = False def forward(self, input): e1, e2, e3, e4 = input # input resnet's feature directly d4 = self.unet_layer4(e4, e3) d3 = self.unet_layer3(d4, e2) d2 = self.unet_layer2(d3, e1) d0 = self.unet_layer0(d2) out = self.conv_last(d0) # 1/2 origin shape return out from mmdet.models.necks.pafpn import PAFPN from mmdet.models import NECKS @NECKS.register_module() class PAFPN_fp32(PAFPN): @force_fp32() def forward(self, inputs): """Forward function.""" assert len(inputs) == len(self.in_channels) # build laterals laterals = [ lateral_conv(inputs[i + self.start_level]) for i, lateral_conv in enumerate(self.lateral_convs) ] # build top-down path used_backbone_levels = len(laterals) for i in range(used_backbone_levels - 1, 0, -1): prev_shape = laterals[i - 1].shape[2:] # fix runtime error of "+=" inplace operation in PyTorch 1.10 laterals[i - 1] = laterals[i - 1] + F.interpolate( laterals[i], size=prev_shape, mode='nearest') # build outputs # part 1: from original levels inter_outs = [ self.fpn_convs[i](laterals[i]) for i in range(used_backbone_levels) ] # part 2: add bottom-up path for i in range(0, used_backbone_levels - 1): inter_outs[i + 1] += self.downsample_convs[i](inter_outs[i]) outs = [] outs.append(inter_outs[0]) outs.extend([ self.pafpn_convs[i - 1](inter_outs[i]) for i in range(1, used_backbone_levels) ]) # part 3: add extra levels if self.num_outs > len(outs): # use max pool to get more levels on top of outputs # (e.g., Faster R-CNN, Mask R-CNN) if not self.add_extra_convs: for i in range(self.num_outs - used_backbone_levels): outs.append(F.max_pool2d(outs[-1], 1, stride=2)) # add conv layers on top of original feature maps (RetinaNet) else: if self.add_extra_convs == 'on_input': orig = inputs[self.backbone_end_level - 1] outs.append(self.fpn_convs[used_backbone_levels](orig)) elif self.add_extra_convs == 'on_lateral': outs.append(self.fpn_convs[used_backbone_levels]( laterals[-1])) elif self.add_extra_convs == 'on_output': outs.append(self.fpn_convs[used_backbone_levels](outs[-1])) else: raise NotImplementedError for i in range(used_backbone_levels + 1, self.num_outs): if self.relu_before_extra_convs: outs.append(self.fpn_convs[i](F.relu(outs[-1]))) else: outs.append(self.fpn_convs[i](outs[-1])) return tuple(outs) @BACKBONES.register_module() class LSS(BaseModule): def __init__(self, x_bound, y_bound, z_bound, d_bound, final_dim, downsample_factor, output_channels, img_backbone_conf, img_neck_conf, depth_net_conf, seg_net_conf=None, queue_len=1, fpn_in_channels=[64, 128, 256, 512]): """Modified from `https://github.com/nv-tlabs/lift-splat-shoot`. Args: x_bound (list): Boundaries for x. y_bound (list): Boundaries for y. z_bound (list): Boundaries for z. d_bound (list): Boundaries for d. final_dim (list): Dimension for input images. downsample_factor (int): Downsample factor between feature map and input image. output_channels (int): Number of channels for the output feature map. img_backbone_conf (dict): Config for image backbone. img_neck_conf (dict): Config for image neck. depth_net_conf (dict): Config for depth net. """ super(LSS, self).__init__() self.downsample_factor = downsample_factor self.fp16_enabled = False self.d_bound = d_bound self.final_dim = final_dim self.output_channels = output_channels self.queue_len = queue_len if self.queue_len!=1: self.bev_multiframe_merge = nn.Conv2d(256*queue_len, 256, kernel_size=3, stride=1, padding=1, bias=False) self.register_buffer( 'voxel_size', torch.Tensor([row[2] for row in [x_bound, y_bound, z_bound]])) self.register_buffer( 'voxel_coord', torch.Tensor([ row[0] + row[2] / 2.0 for row in [x_bound, y_bound, z_bound] ])) self.register_buffer( 'voxel_num', torch.LongTensor([(row[1] - row[0]) / row[2] for row in [x_bound, y_bound, z_bound]])) self.register_buffer('frustum', self.create_frustum()) self.depth_channels, _, _, _ = self.frustum.shape self.img_backbone = build_backbone(img_backbone_conf) self.img_neck = build_neck(img_neck_conf) self.neck_conv = nn.Conv2d(in_channels=img_neck_conf["out_channels"], out_channels=depth_net_conf["in_channels"], kernel_size=1) self.depth_net = self._configure_depth_net(depth_net_conf) self.seg_net = self._configure_seg_net(seg_net_conf, fpn_in_channels) self.seg_res_to_image_feature =nn.Sequential( nn.Conv2d(seg_net_conf['out_channels'], 64, 1), nn.BatchNorm2d(64), nn.ReLU(), nn.Conv2d(64, 16, 1), nn.BatchNorm2d(16), nn.ReLU(), nn.Conv2d(16, 32, 3, padding=1, stride=2), nn.BatchNorm2d(32), nn.ReLU(), nn.Conv2d(32, 32, 1), nn.BatchNorm2d(32), nn.ReLU(), nn.Conv2d(32, 64, 3, padding=1, stride=2), nn.BatchNorm2d(64), nn.ReLU(), nn.Conv2d(64, 64, 1), nn.BatchNorm2d(64), nn.ReLU(), nn.Conv2d(64, 128, 3, padding=1, stride=2), nn.BatchNorm2d(128), nn.ReLU(), ) self.merge_seg_and_image = nn.Conv2d(256+128, 256, 3, padding=1) self.img_neck.init_weights() self.img_backbone.init_weights() def _configure_depth_net(self, depth_net_conf): return DepthNet( depth_net_conf['in_channels'], depth_net_conf['mid_channels'], self.output_channels, self.depth_channels, ) def _configure_seg_net(self, seg_net_conf, fpn_in_channels): return UNet(seg_net_conf['out_channels'], fpn_in_channels) def create_frustum(self): """Generate frustum""" # make grid in image plane ogfH, ogfW = self.final_dim fH, fW = ogfH // self.downsample_factor, ogfW // self.downsample_factor d_coords = torch.arange(*self.d_bound, dtype=torch.float).view(-1, 1, 1).expand(-1, fH, fW) D, _, _ = d_coords.shape x_coords = torch.linspace(0, ogfW - 1, fW, dtype=torch.float).view( 1, 1, fW).expand(D, fH, fW) y_coords = torch.linspace(0, ogfH - 1, fH, dtype=torch.float).view(1, fH, 1).expand(D, fH, fW) paddings = torch.ones_like(d_coords) # D x H x W x 3 frustum = torch.stack((x_coords, y_coords, d_coords, paddings), -1) return frustum @force_fp32() def get_geometry(self, sensor2ego_mat, intrin_mat, ida_mat, bda_mat): """Transfer points from camera coord to ego coord. Args: rots(Tensor): Rotation matrix from camera to ego. trans(Tensor): Translation matrix from camera to ego. intrins(Tensor): Intrinsic matrix. post_rots_ida(Tensor): Rotation matrix for ida. post_trans_ida(Tensor): Translation matrix for ida post_rot_bda(Tensor): Rotation matrix for bda. Returns: Tensors: points ego coord. """ batch_size, num_cams, _, _ = sensor2ego_mat.shape # undo post-transformation # B x N x D x H x W x 3 points = self.frustum ida_mat = ida_mat.view(batch_size, num_cams, 1, 1, 1, 4, 4) ## ida_mat = aug_img2img ## img2aug_img points = ida_mat.inverse().matmul(points.unsqueeze(-1)) # B,N,D,H,W,4,1 # cam_to_ego points = torch.cat( (points[:, :, :, :, :, :2] * points[:, :, :, :, :, 2:3], # x/y * z points[:, :, :, :, :, 2:]), 5) combine = sensor2ego_mat.matmul(torch.inverse(intrin_mat)) # cam2lidar @ img2cam --> img2lidar points = combine.view(batch_size, num_cams, 1, 1, 1, 4, 4).matmul(points) if bda_mat is not None: bda_mat = bda_mat.unsqueeze(1).repeat(1, num_cams, 1, 1).view( batch_size, num_cams, 1, 1, 1, 4, 4) points = (bda_mat @ points).squeeze(-1) else: points = points.squeeze(-1) return points[..., :3] @auto_fp16() def get_cam_feats(self, imgs): """Get feature maps from images.""" batch_size, num_sweeps, num_cams, num_channels, imH, imW = imgs.shape imgs = imgs.flatten().view(batch_size * num_sweeps * num_cams, num_channels, imH, imW) fpn_feats = self.img_backbone(imgs) fpn_feats = self.img_neck(fpn_feats) img_feats = self.neck_conv_fp32(fpn_feats[2]) img_feats = img_feats.reshape(batch_size, num_sweeps, num_cams, img_feats.shape[1], img_feats.shape[2], img_feats.shape[3]) return img_feats, fpn_feats @force_fp32() def neck_conv_fp32(self, input): return self.neck_conv(input) @force_fp32() def _forward_depth_net(self, feat, mats_dict): return self.depth_net(feat, mats_dict) @auto_fp16() def _forward_voxel_net(self, img_feat_with_depth): return img_feat_with_depth @auto_fp16() def _forward_single_sweep(self, sweep_index, sweep_imgs, mats_dict, is_return_depth=False): """Forward function for single sweep. Args: sweep_index (int): Index of sweeps. sweep_imgs (Tensor): Input images. mats_dict (dict): sensor2ego_mats(Tensor): Transformation matrix from camera to ego with shape of (B, num_sweeps, num_cameras, 4, 4). intrin_mats(Tensor): Intrinsic matrix with shape of (B, num_sweeps, num_cameras, 4, 4). ida_mats(Tensor): Transformation matrix for ida with shape of (B, num_sweeps, num_cameras, 4, 4). sensor2sensor_mats(Tensor): Transformation matrix from key frame camera to sweep frame camera with shape of (B, num_sweeps, num_cameras, 4, 4). is_return_depth (bool, optional): Whether to return depth. Default: False. Returns: Tensor: BEV feature map. """ batch_size, num_sweeps, num_cams, num_channels, img_height, \ img_width = sweep_imgs.shape img_feats, fpn_feats = self.get_cam_feats(sweep_imgs) source_features = img_feats[:, 0, ...] source_features = source_features.reshape(batch_size * num_cams, source_features.shape[2], source_features.shape[3], source_features.shape[4]) depth_feature = self._forward_depth_net( source_features, mats_dict, ) depth = depth_feature[:, :self.depth_channels] depth_softmax = depth.softmax(1) img_feature = depth_feature[:, self.depth_channels:(self.depth_channels + self.output_channels)] ## Map 2D Segmentation to BEV as well seg_output = self.seg_net(fpn_feats) # 1/2 origin shape seg_feature = self.seg_res_to_image_feature_forward(seg_output.detach())# 1/16 origin shape img_feature = torch.cat((img_feature, seg_feature), dim=1) img_feature = self.merge_seg_and_image(img_feature) # keep same dims img_feat_with_depth = depth_softmax.unsqueeze(1) * img_feature.unsqueeze(2) outs = {} outs["fpn_feats"] = fpn_feats img_feat_with_depth = self._forward_voxel_net(img_feat_with_depth) img_feat_with_depth = img_feat_with_depth.reshape( batch_size, num_cams, img_feat_with_depth.shape[1], img_feat_with_depth.shape[2], img_feat_with_depth.shape[3], img_feat_with_depth.shape[4], ) geom_xyz = self.get_geometry( mats_dict['sensor2ego_mats'][:, sweep_index, ...], mats_dict['intrin_mats'][:, sweep_index, ...], mats_dict['ida_mats'][:, sweep_index, ...], mats_dict.get('bda_mat', None), ) img_feat_with_depth = img_feat_with_depth.permute(0, 1, 3, 4, 5, 2) feature_map = self.voxel_pooling_method(geom_xyz, img_feat_with_depth.contiguous(), self.voxel_num.to(img_feat_with_depth.device)) outs["bev"] = feature_map.contiguous() if is_return_depth: outs['depth'] = depth outs['seg'] = seg_output return outs @force_fp32() def seg_res_to_image_feature_forward(self, input): return self.seg_res_to_image_feature(input) @force_fp32() def voxel_pooling_method(self, geom_xyz, img_feat_with_depth, voxel_num): geom_xyz = ((geom_xyz - (self.voxel_coord - self.voxel_size / 2.0)) / self.voxel_size).int() return voxel_pooling(geom_xyz, img_feat_with_depth, voxel_num) @auto_fp16() def forward(self, img, img_metas, timestamps=None, is_return_depth=False): """Forward function. Args: sweep_imgs(Tensor): Input images with shape of (B, num_sweeps, num_cameras, 3, H, W). mats_dict(dict): sensor2ego_mats(Tensor): Transformation matrix from camera to ego with shape of (B, num_sweeps, num_cameras, 4, 4). intrin_mats(Tensor): Intrinsic matrix with shape of (B, num_sweeps, num_cameras, 4, 4). ida_mats(Tensor): Transformation matrix for ida with shape of (B, num_sweeps, num_cameras, 4, 4). sensor2sensor_mats(Tensor): Transformation matrix from key frame camera to sweep frame camera with shape of (B, num_sweeps, num_cameras, 4, 4). timestamps(Tensor): Timestamp for all images with the shape of(B, num_sweeps, num_cameras). Return: Tensor: bev feature map. """ if img.dim() == 5: img = img.unsqueeze(1) batch_size, num_sweeps, num_cams, num_channels, img_height, \ img_width = img.shape intrins, ida, sensor2ego = [], [], [] for b in range(len(img_metas)): _intrins, _ida, _sensor2ego = [], [], [] for sweep_idx in range(len(img_metas[0])): mats = img_metas[b][sweep_idx] intrinsic_mat = torch.zeros((num_cams,4,4)) intrinsic_mat[:,:3,:3] = mats['cam_intrinsic'] intrinsic_mat[:,3,3] = 1 _intrins.append(intrinsic_mat) _ida.append(mats['ida_mats']) # Nx4x4 _sensor2ego.append(mats['currlidar2keycam'].permute(0,2,1)) # cam2lidar intrins.append(torch.stack(_intrins)) sensor2ego.append(torch.stack(_sensor2ego)) ida.append(torch.stack(_ida)) intrins, ida, sensor2ego = torch.stack(intrins), torch.stack(ida), torch.stack(sensor2ego) old_img_metas = img_metas img_metas = {} img_metas['intrin_mats'] = intrins.to(img.device) img_metas['sensor2ego_mats'] = sensor2ego.to(img.device) img_metas['ida_mats'] = ida.to(img.device) key_frame_res = self._forward_single_sweep( -1, img[:, -1:, ...], img_metas, is_return_depth=is_return_depth) outs = {} bev_feature_list = [key_frame_res['bev']] if self.seg_net is not None: outs['seg'] = key_frame_res['seg'] if is_return_depth: outs['depth'] = key_frame_res['depth'] outs["fpn_feats"] = key_frame_res["fpn_feats"] current_ida = ida[:, -1, :, :].clone() #B, 4, 4, 4 current_lidar2img = torch.stack([_[-1]["lidar2img"] for _ in old_img_metas], dim=0) outs['lidar2img'] = current_lidar2img outs['ida_mat'] = current_ida # multi-frame for sweep_index in range(1, num_sweeps): with torch.no_grad(): sweep_frame_res = self._forward_single_sweep( -sweep_index, img[:, -(sweep_index+1):-sweep_index, ...], img_metas, is_return_depth=False) bev_feature_list.append(sweep_frame_res['bev']) assert len(bev_feature_list)==self.queue_len, 'LSS.queue_len must be set correctly in config!' bev_feature = torch.cat(bev_feature_list, 1) if self.queue_len>1: bev_feature = self.bev_multiframe_merge(bev_feature) outs['bev'] = bev_feature return outs ================================================ FILE: open_loop_training/code/model_code/dense_heads/__init__.py ================================================ from .thinktwice_decoder import ThinkTwiceDecoder ================================================ FILE: open_loop_training/code/model_code/dense_heads/multi_scale_deformable_attn_function.py ================================================ # --------------------------------------------- # Copyright (c) OpenMMLab. All rights reserved. # --------------------------------------------- # Modified by Zhiqi Li # Modified by Xiaosong Jia # --------------------------------------------- import torch from torch.cuda.amp import custom_bwd, custom_fwd from torch.autograd.function import Function, once_differentiable from mmcv.utils import ext_loader import torch.nn as nn import torch.nn.functional as F from mmcv.cnn import xavier_init, constant_init from mmcv.cnn.bricks.registry import (ATTENTION, TRANSFORMER_LAYER_SEQUENCE) from mmcv.cnn.bricks.transformer import TransformerLayerSequence import math from mmcv.runner.base_module import BaseModule, ModuleList, Sequential from mmcv.utils import (ConfigDict, build_from_cfg, deprecated_api_warning, to_2tuple) from mmcv.ops.multi_scale_deform_attn import multi_scale_deformable_attn_pytorch from mmcv.utils import ext_loader ext_module = ext_loader.load_ext( '_ext', ['ms_deform_attn_backward', 'ms_deform_attn_forward']) from mmcv.runner import force_fp32, auto_fp16 def inverse_sigmoid(x, eps=1e-5): """Inverse function of sigmoid. Args: x (Tensor): The tensor to do the inverse. eps (float): EPS avoid numerical overflow. Defaults 1e-5. Returns: Tensor: The x has passed the inverse function of sigmoid, has same shape with input. """ x = x.clamp(min=0, max=1) x1 = x.clamp(min=eps) x2 = (1 - x).clamp(min=eps) return torch.log(x1 / x2) class MultiScaleDeformableAttnFunction_fp16(Function): @staticmethod @custom_fwd(cast_inputs=torch.float16) def forward(ctx, value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights, im2col_step): """GPU version of multi-scale deformable attention. Args: value (Tensor): The value has shape (bs, num_keys, mum_heads, embed_dims//num_heads) value_spatial_shapes (Tensor): Spatial shape of each feature map, has shape (num_levels, 2), last dimension 2 represent (h, w) sampling_locations (Tensor): The location of sampling points, has shape (bs ,num_queries, num_heads, num_levels, num_points, 2), the last dimension 2 represent (x, y). attention_weights (Tensor): The weight of sampling points used when calculate the attention, has shape (bs ,num_queries, num_heads, num_levels, num_points), im2col_step (Tensor): The step used in image to column. Returns: Tensor: has shape (bs, num_queries, embed_dims) """ ctx.im2col_step = im2col_step output = ext_module.ms_deform_attn_forward( value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights, im2col_step=ctx.im2col_step) ctx.save_for_backward(value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights) return output @staticmethod @once_differentiable @custom_bwd def backward(ctx, grad_output): """GPU version of backward function. Args: grad_output (Tensor): Gradient of output tensor of forward. Returns: Tuple[Tensor]: Gradient of input tensors in forward. """ value, value_spatial_shapes, value_level_start_index, \ sampling_locations, attention_weights = ctx.saved_tensors grad_value = torch.zeros_like(value) grad_sampling_loc = torch.zeros_like(sampling_locations) grad_attn_weight = torch.zeros_like(attention_weights) ext_module.ms_deform_attn_backward( value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights, grad_output.contiguous(), grad_value, grad_sampling_loc, grad_attn_weight, im2col_step=ctx.im2col_step) return grad_value, None, None, \ grad_sampling_loc, grad_attn_weight, None class MultiScaleDeformableAttnFunction_fp32(Function): @staticmethod @custom_fwd(cast_inputs=torch.float32) def forward(ctx, value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights, im2col_step): """GPU version of multi-scale deformable attention. Args: value (Tensor): The value has shape (bs, num_keys, mum_heads, embed_dims//num_heads) value_spatial_shapes (Tensor): Spatial shape of each feature map, has shape (num_levels, 2), last dimension 2 represent (h, w) sampling_locations (Tensor): The location of sampling points, has shape (bs ,num_queries, num_heads, num_levels, num_points, 2), the last dimension 2 represent (x, y). attention_weights (Tensor): The weight of sampling points used when calculate the attention, has shape (bs ,num_queries, num_heads, num_levels, num_points), im2col_step (Tensor): The step used in image to column. Returns: Tensor: has shape (bs, num_queries, embed_dims) """ ctx.im2col_step = im2col_step output = ext_module.ms_deform_attn_forward( value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights, im2col_step=ctx.im2col_step) ctx.save_for_backward(value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights) return output @staticmethod @once_differentiable @custom_bwd def backward(ctx, grad_output): """GPU version of backward function. Args: grad_output (Tensor): Gradient of output tensor of forward. Returns: Tuple[Tensor]: Gradient of input tensors in forward. """ value, value_spatial_shapes, value_level_start_index, \ sampling_locations, attention_weights = ctx.saved_tensors grad_value = torch.zeros_like(value) grad_sampling_loc = torch.zeros_like(sampling_locations) grad_attn_weight = torch.zeros_like(attention_weights) ext_module.ms_deform_attn_backward( value, value_spatial_shapes, value_level_start_index, sampling_locations, attention_weights, grad_output.contiguous(), grad_value, grad_sampling_loc, grad_attn_weight, im2col_step=ctx.im2col_step) return grad_value, None, None, \ grad_sampling_loc, grad_attn_weight, None class PositionwiseFeedForward(nn.Module): ''' A two-feed-forward-layer module ''' def __init__(self, d_in, d_hid, dropout=0.0): super().__init__() self.norm = nn.LayerNorm(d_in) self.w_1 = nn.Linear(d_in, d_hid) self.w_2 = nn.Linear(d_hid, d_in) # position-wise self.act = F.gelu self.dropout = nn.Dropout(dropout) xavier_init(self.w_1, distribution='normal', bias=0.) xavier_init(self.w_2, distribution='normal', bias=0.) nn.init.constant_(self.norm.weight, 1) nn.init.constant_(self.norm.bias, 0) def forward(self, x): residual = x output = self.w_2(self.act(self.w_1(self.norm(x)))) output = self.dropout(output) + residual return output class SpatialCrossAttention(BaseModule): """An attention module used in BEVFormer. Args: embed_dims (int): The embedding dimension of Attention. Default: 256. num_cams (int): The number of cameras dropout (float): A Dropout layer on `inp_residual`. Default: 0.. init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization. Default: None. deformable_attention: (dict): The config for the deformable attention used in SCA. """ def __init__(self, embed_dims=256, num_cams=4, dropout=0.0, init_cfg=None, batch_first=True, deformable_attention=dict( type='MSDeformableAttention3D', embed_dims=256, num_levels=4), query_dims=1543, **kwargs ): super(SpatialCrossAttention, self).__init__(init_cfg) self.init_cfg = init_cfg self.dropout = nn.Dropout(dropout) self.fp16_enabled = False self.deformable_attention = MSDeformableAttention3D() self.embed_dims = embed_dims self.num_cams = num_cams self.batch_first = batch_first self.query_linear = nn.Sequential( nn.LayerNorm(query_dims), nn.Linear(query_dims, 512), nn.GELU(), nn.Linear(512, embed_dims), nn.GELU() ) self.dropout = nn.Dropout(dropout) self.ffn = PositionwiseFeedForward(256, 1024) self.output_proj = nn.Sequential( nn.LayerNorm(int(self.num_cams*256)), nn.Linear(int(self.num_cams*256), 512), nn.GELU(), nn.Linear(512, embed_dims), ) self.init_weight() def init_weight(self): """Default initialization for Parameters of Module.""" nn.init.constant_(self.query_linear[0].weight, 1) nn.init.constant_(self.query_linear[0].bias, 0) xavier_init(self.query_linear[1], distribution='normal', bias=0.) xavier_init(self.query_linear[3], distribution='normal', bias=0.) xavier_init(self.output_proj, distribution='normal', bias=0.) @force_fp32(apply_to=('query', 'key', 'value', 'query_pos', 'reference_points_cam')) def forward(self, query, key=None, value=None, residual=None, query_pos=None, key_padding_mask=None, reference_points=None, spatial_shapes=None, reference_points_cam=None, bev_mask=None, level_start_index=None, indexes=None, flag='encoder', **kwargs): """Forward Function of Detr3DCrossAtten. Args: query (Tensor): Query of Transformer with shape (num_query, bs, embed_dims). key (Tensor): The key tensor with shape `(num_key, bs, embed_dims)`. value (Tensor): The value tensor with shape `(num_key, bs, embed_dims)`. (B, N, C, H, W) residual (Tensor): The tensor used for addition, with the same shape as `x`. Default None. If None, `x` will be used. query_pos (Tensor): The positional encoding for `query`. Default: None. key_pos (Tensor): The positional encoding for `key`. Default None. reference_points (Tensor): The normalized reference points with shape (bs, num_query, 4), all elements is range in [0, 1], top-left (0,0), bottom-right (1, 1), including padding area. or (N, Length_{query}, num_levels, 4), add additional two dimensions is (w, h) to form reference boxes. key_padding_mask (Tensor): ByteTensor for `query`, with shape [bs, num_key]. spatial_shapes (Tensor): Spatial shape of features in different level. With shape (num_levels, 2), last dimension represent (h, w). level_start_index (Tensor): The start index of each level. A tensor has shape (num_levels) and can be represented as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...]. Returns: Tensor: forwarded results with shape [num_query, bs, embed_dims]. """ query = self.query_linear(query) bs, num_cams, max_len, _ = query.size() num_cams, l, bs, embed_dims = value.shape value = value.permute(2, 0, 1, 3).reshape( bs * self.num_cams, l, self.embed_dims) queries = self.dropout(self.deformable_attention( query=query.view(bs*self.num_cams, max_len, self.embed_dims), key=value, value=value, reference_points=reference_points.view(bs*self.num_cams, max_len, 2), spatial_shapes=spatial_shapes, level_start_index=level_start_index).view(bs, self.num_cams, max_len, self.embed_dims)) queries = self.ffn(queries) for j in range(bs): for i, index_query_per_img in enumerate(indexes): queries[j, i, :len(index_query_per_img)] = 0 queries[j, i] /= max(len(index_query_per_img), 1.0) queries = queries.sum(-2).view(bs, -1) queries = self.output_proj(queries) return queries class MSDeformableAttention3D(BaseModule): """An attention module used in BEVFormer based on Deformable-Detr. `Deformable DETR: Deformable Transformers for End-to-End Object Detection. `_. Args: embed_dims (int): The embedding dimension of Attention. Default: 256. num_heads (int): Parallel attention heads. Default: 64. num_levels (int): The number of feature map used in Attention. Default: 4. num_points (int): The number of sampling points for each query in each head. Default: 4. im2col_step (int): The step used in image_to_column. Default: 64. dropout (float): A Dropout layer on `inp_identity`. Default: 0.1. batch_first (bool): Key, Query and Value are shape of (batch, n, embed_dim) or (n, batch, embed_dim). Default to False. norm_cfg (dict): Config dict for normalization layer. Default: None. init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization. Default: None. """ def __init__(self, embed_dims=256, num_heads=8, num_levels=4, num_points=8, im2col_step=64, dropout=0.0, batch_first=True, norm_cfg=None, init_cfg=None): super().__init__(init_cfg) if embed_dims % num_heads != 0: raise ValueError(f'embed_dims must be divisible by num_heads, ' f'but got {embed_dims} and {num_heads}') dim_per_head = embed_dims // num_heads self.norm_cfg = norm_cfg self.batch_first = batch_first self.output_proj = None self.fp16_enabled = False self.im2col_step = im2col_step self.embed_dims = embed_dims self.num_levels = num_levels self.num_heads = num_heads self.num_points = num_points self.sampling_offsets = nn.Linear( embed_dims, num_heads * num_levels * num_points * 2) self.attention_weights = nn.Linear(embed_dims, num_heads * num_levels * num_points) self.value_proj = nn.Linear(embed_dims, embed_dims) self.init_weights() def init_weights(self): """Default initialization for Parameters of Module.""" constant_init(self.sampling_offsets, 0.) thetas = torch.arange( self.num_heads, dtype=torch.float32) * (2.0 * math.pi / self.num_heads) grid_init = torch.stack([thetas.cos(), thetas.sin()], -1) grid_init = (grid_init / grid_init.abs().max(-1, keepdim=True)[0]).view( self.num_heads, 1, 1, 2).repeat(1, self.num_levels, self.num_points, 1) for i in range(self.num_points): grid_init[:, :, i, :] *= i + 1 self.sampling_offsets.bias.data = grid_init.view(-1) constant_init(self.attention_weights, val=0., bias=0.) xavier_init(self.value_proj, distribution='uniform', bias=0.) xavier_init(self.output_proj, distribution='uniform', bias=0.) self._is_init = True def forward(self, query, key=None, value=None, identity=None, query_pos=None, key_padding_mask=None, reference_points=None, spatial_shapes=None, level_start_index=None, **kwargs): """Forward Function of MultiScaleDeformAttention. Args: query (Tensor): Query of Transformer with shape ( bs, num_query, embed_dims). key (Tensor): The key tensor with shape `(bs, num_key, embed_dims)`. value (Tensor): The value tensor with shape `(bs, num_key, embed_dims)`. identity (Tensor): The tensor used for addition, with the same shape as `query`. Default None. If None, `query` will be used. query_pos (Tensor): The positional encoding for `query`. Default: None. key_pos (Tensor): The positional encoding for `key`. Default None. reference_points (Tensor): The normalized reference points with shape (bs, num_query, num_levels, 2), all elements is range in [0, 1], top-left (0,0), bottom-right (1, 1), including padding area. or (N, Length_{query}, num_levels, 4), add additional two dimensions is (w, h) to form reference boxes. key_padding_mask (Tensor): ByteTensor for `query`, with shape [bs, num_key]. spatial_shapes (Tensor): Spatial shape of features in different levels. With shape (num_levels, 2), last dimension represents (h, w). level_start_index (Tensor): The start index of each level. A tensor has shape ``(num_levels, )`` and can be represented as [0, h_0*w_0, h_0*w_0+h_1*w_1, ...]. Returns: Tensor: forwarded results with shape [num_query, bs, embed_dims]. """ if value is None: value = query bs, num_query, _ = query.shape bs, num_value, _ = value.shape assert (spatial_shapes[:, 0] * spatial_shapes[:, 1]).sum() == num_value value = self.value_proj(value) # if key_padding_mask is not None: # value = value.masked_fill(key_padding_mask[..., None], 0.0) value = value.view(bs, num_value, self.num_heads, -1) sampling_offsets = self.sampling_offsets(query).view( bs, num_query, self.num_heads, self.num_levels, self.num_points, 2) attention_weights = self.attention_weights(query).view( bs, num_query, self.num_heads, self.num_levels * self.num_points) attention_weights = attention_weights.softmax(-1) attention_weights = attention_weights.view(bs, num_query, self.num_heads, self.num_levels, self.num_points) if reference_points.shape[-1] == 2: """ For each BEV query, it owns `num_Z_anchors` in 3D space that having different heights. After proejcting, each BEV query has `num_Z_anchors` reference points in each 2D image. For each referent point, we sample `num_points` sampling points. For `num_Z_anchors` reference points, it has overall `num_points * num_Z_anchors` sampling points. """ offset_normalizer = torch.stack( [spatial_shapes[..., 1], spatial_shapes[..., 0]], -1) bs, num_query, xy = reference_points.shape reference_points = reference_points[:, :, None, None, None, :] sampling_offsets = sampling_offsets / offset_normalizer[None, None, None, :, None, :] bs, num_query, num_heads, num_levels, num_all_points, xy = sampling_offsets.shape sampling_locations = reference_points + sampling_offsets #bs, num_query, num_heads, num_levels, num_all_points, xy = sampling_locations.shape else: raise ValueError( f'Last dim of reference_points must be' f' 2 or 4, but get {reference_points.shape[-1]} instead.') # sampling_locations.shape: bs, num_query, num_heads, num_levels, num_all_points, 2 # attention_weights.shape: bs, num_query, num_heads, num_levels, num_all_points if torch.cuda.is_available() and value.is_cuda: if value.dtype == torch.float16: MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32 else: MultiScaleDeformableAttnFunction = MultiScaleDeformableAttnFunction_fp32 output = MultiScaleDeformableAttnFunction.apply( value, spatial_shapes, level_start_index, sampling_locations, attention_weights, self.im2col_step) else: output = multi_scale_deformable_attn_pytorch( value, spatial_shapes, sampling_locations, attention_weights) return output ================================================ FILE: open_loop_training/code/model_code/dense_heads/thinktwice_decoder.py ================================================ import copy from collections import OrderedDict from distutils.errors import LibError from .multi_scale_deformable_attn_function import SpatialCrossAttention from .utils import SpatialGRU, sigmoid_focal_loss, init_weights from mmcv.cnn import build_conv_layer import torch import torch.nn as nn import torch.nn.functional as F from torch.distributions import Beta from mmdet.core import (multi_apply, multi_apply, reduce_mean) from mmdet.models import HEADS from mmcv.runner import BaseModule import numpy as np import mmcv import cv2 as cv from mmcv.runner import force_fp32, auto_fp16 def inv_softplus(x): return x + torch.log(-torch.expm1(-x)) class PredictionModule(nn.Module): def __init__(self, act): super().__init__() self.act = act self.spatial_gru = SpatialGRU(input_size=6, hidden_size=32, act=self.act) ## Resiudal Update self.ffn = nn.Sequential( nn.Conv2d(32, 64, kernel_size=1), self.act(), nn.Conv2d(64, 32, kernel_size=3, padding=1), self.act(), nn.Conv2d(32, 32, kernel_size=1), ) @force_fp32() def forward(self, current_BEV_feature, current_wp, current_ctrl, future_bev_feat_from_last_layer): future_bev_feat = self.spatial_gru(torch.cat([current_wp, current_ctrl], dim=2).unsqueeze(-1).unsqueeze(-1).repeat(1, 1, 1, current_BEV_feature.shape[-2], current_BEV_feature.shape[-1]), state=current_BEV_feature).view(-1, current_BEV_feature.shape[1], current_BEV_feature.shape[2], current_BEV_feature.shape[3]) ## Residual Update if future_bev_feat_from_last_layer is not None: current_future_bev_feat = self.ffn(future_bev_feat) + future_bev_feat_from_last_layer.view(-1, current_BEV_feature.shape[1], current_BEV_feature.shape[2], current_BEV_feature.shape[3]) return future_bev_feat class LookModule(nn.Module): def __init__(self, act): super().__init__() self.act = act self.cam_look_module = SpatialCrossAttention() self.lidar_look_module_atten = nn.Sequential( nn.Linear(6+128, 256), self.act(), nn.Linear(256, 512), nn.Sigmoid(), ) self.lidar_look_module_MLP = nn.Sequential( nn.Linear(512, 128), self.act(), nn.Flatten(start_dim=2), nn.Linear(9*128, 256), self.act(), ) self.look_feature_MLP = nn.Sequential( nn.Linear(512*4, 512), self.act(), nn.Linear(512, 128), ) self.point_cloud_range = [-8.0, -19.2, -4.0, 30.4, 19.2, 4.0] self.fp16_enabled = False @force_fp32() def obtain_lidar_look_features(self, wp, lidar_grid): bs, T, xy = wp.size() relative_wp_x = 1.0 - torch.clamp(((wp[..., 0] - self.point_cloud_range[0])/(self.point_cloud_range[3]-self.point_cloud_range[0])).unsqueeze(-1) + torch.Tensor([0.0, -0.1, 0.1]).unsqueeze(0).unsqueeze(0).to(wp.device), min=0.0, max=1.0) relative_wp_y = torch.clamp(((wp[..., 1] - self.point_cloud_range[1])/(self.point_cloud_range[4]-self.point_cloud_range[1])).unsqueeze(-1) + torch.Tensor([0.0, -0.1, 0.1]).unsqueeze(0).unsqueeze(0).to(wp.device), min=0.0, max=1.0) relative_wp = torch.stack([relative_wp_x.unsqueeze(-1).repeat(1, 1, 1, 3), relative_wp_y.unsqueeze(-2).repeat(1, 1, 3, 1)], dim=-1).view(bs*T, -1, 1, 2) * 2 - 1 sampled_feat = F.grid_sample(input=lidar_grid.view(bs*T, *lidar_grid.shape[2:]), grid=relative_wp, align_corners=False).view(bs, T, -1, 9).transpose(2, 3) return sampled_feat @force_fp32() def obtain_cam_ref_points_query(self, reference_points, transform_mat, img_shape, query, mlvl_feats): reference_points = torch.cat((reference_points, torch.ones_like(reference_points[..., :1])), -1) # reference_points (B, num_queries, 4) B, num_query = reference_points.size()[:2] num_cam = transform_mat[0].size(1) reference_points = reference_points.view(B, 1, num_query, 4).repeat(1, num_cam, 1, 1).unsqueeze(-1) lidar2img = transform_mat[0].view(B, num_cam, 1, 4, 4).repeat(1, 1, num_query, 1, 1) ida_mat = transform_mat[1].view(B, num_cam, 1, 4, 4).repeat(1, 1, num_query, 1, 1) reference_points_cam = torch.matmul(lidar2img, reference_points).squeeze(-1) eps = 1e-5 new_reference_points_cam = reference_points_cam.clone() new_reference_points_cam[..., 0:2] = reference_points_cam[..., 0:2] / torch.maximum( reference_points_cam[..., 2:3], torch.ones_like(reference_points_cam[..., 2:3])*eps) reference_points_cam = torch.matmul(ida_mat, new_reference_points_cam.unsqueeze(-1)).squeeze(-1) mask = (reference_points_cam[..., 2:3] > eps) reference_points_cam = reference_points_cam[..., :2] reference_points_cam[..., 0] /= img_shape[1] reference_points_cam[..., 1] /= img_shape[0]#B x Cam x Num_query x 2 mask = (mask & (reference_points_cam[..., 1:2] > 0.0) & (reference_points_cam[..., 1:2] < 1.0) & (reference_points_cam[..., 0:1] < 1.0) & (reference_points_cam[..., 0:1] > 0.0)) mask = mask.view(B, num_cam, num_query) mask = torch.nan_to_num(mask) mask = mask.permute(1, 0, 2) sampled_feats = [] N = 4 reference_points_cam_lvl = reference_points_cam.view(B*N, num_query, 1, 2) * 2 -1.0 for lvl, feat in enumerate(mlvl_feats): BN, C, H, W = feat.size() B = int(BN/N) #feat = feat.view(B*N, C, H, W) sampled_feat = F.grid_sample(feat, reference_points_cam_lvl, align_corners=False) sampled_feat = sampled_feat.view(B, N, C, num_query, 1).permute(0, 2, 3, 1, 4) sampled_feats.append(sampled_feat) sampled_feats = torch.stack(sampled_feats, -1) sampled_feats = sampled_feats.view(B, C, num_query, num_cam, len(mlvl_feats)).permute(0, 2, 3, 1, 4).reshape(B, num_query, num_cam, -1) indexes = [] # From bev_mask of each image, to obtain the available queries' index for i, mask_per_img in enumerate(mask): tmp_index = [] for j in range(B): index_query_per_img = mask_per_img[j].nonzero().squeeze(-1) tmp_index.append(index_query_per_img) indexes.append(tmp_index) max_len = max([len(each_sample) for each_cam in indexes for each_sample in each_cam]) bs, num_query, query_emb = query.shape num_cams = 4 queries_rebatch = query.new_zeros([bs * num_cams, max_len, query_emb+1024]) reference_points_rebatch = reference_points_cam.new_zeros([bs * num_cams, max_len, 2]) reference_points_cam = reference_points_cam.permute(1, 0, 2, 3) for i, reference_points_per_img in enumerate(reference_points_cam): for j in range(bs): index_query_per_img = indexes[i][j] if len(index_query_per_img) != 0: queries_rebatch[j * num_cams + i, :len(index_query_per_img)] = torch.cat([query[j, index_query_per_img], sampled_feats[j, index_query_per_img, i]], dim=-1) reference_points_rebatch[j * num_cams + i, :len(index_query_per_img)] = reference_points_per_img[j, index_query_per_img] return reference_points_rebatch.view(bs, num_cams, max_len, 2), queries_rebatch.view(bs, num_cams, max_len, query_emb+1024), indexes @force_fp32() def forward(self, current_wp, current_ctrl_softplus, measurement_feat, flattened_feat, coor2img, img_size, mlvl_feats, fpn_feat_flatten, spatial_shapes, level_start_index, lidar_feat_with_high_resolution, temporal_embedding, static_embedding): # Look Module - Image ## Avoid empty points situation which could cause bugs in code static_point = torch.Tensor([[5.0, 0.0], [0.0, -5.0], [0.0, 5.0], [-5.0, 0.0],]).unsqueeze(0).repeat(current_wp.shape[0], 1, 1).to(current_wp.device) look_wp = torch.cat([current_wp, static_point], dim=1) ### Add z to 2D BEV coordinate uniformly look_wp_3d = torch.cat([look_wp.unsqueeze(2).repeat(1, 1, 15, 1), torch.linspace(-4, 10, 15, dtype=float, device=look_wp.device).unsqueeze(0).unsqueeze(0).unsqueeze(-1).repeat(look_wp.shape[0], look_wp.shape[1], 1, 1)], dim=-1).view(look_wp.shape[0], -1, 3).to(look_wp.device, look_wp.dtype) # B x T x z_level x 3 -> B x T*z_level x 3 input_ctrl = torch.cat([current_ctrl_softplus.unsqueeze(2).repeat(1, 1, 15, 1).view(current_ctrl_softplus.shape[0], -1, 4), torch.zeros(current_wp.shape[0], 4*15, 4).to(current_wp.device)], dim=1) ## No control for static points ## For deformable Attn img_query = torch.cat([ input_ctrl, ## predicted control look_wp_3d, ## predict traj torch.cat([temporal_embedding.unsqueeze(0).unsqueeze(-2).repeat(current_wp.shape[0], 1, 15, 1).view(current_wp.shape[0], -1, temporal_embedding.shape[-1]), ## Temporal Emeddding static_embedding.unsqueeze(0).unsqueeze(-2).repeat(current_wp.shape[0], 1, 15, 1).view(current_wp.shape[0], -1, temporal_embedding.shape[-1])], dim=1), ## Static Point Embedding measurement_feat.unsqueeze(1).repeat(1, look_wp_3d.shape[1], 1), flattened_feat.unsqueeze(1).repeat(1, look_wp_3d.shape[1], 1) ], dim=-1) #B x T*z_level * 4 + 3 + 128 + 128 + 256 ## Transform into the desired format for the deformable attention ref_points_cam_rebatch, query_rebatch, indexes_rebatch = self.obtain_cam_ref_points_query(look_wp_3d, coor2img, img_size, img_query, mlvl_feats) img_look_features = self.cam_look_module(query=query_rebatch, value=fpn_feat_flatten, reference_points=ref_points_cam_rebatch, spatial_shapes=spatial_shapes, level_start_index=level_start_index, indexes=indexes_rebatch) img_look_features = img_look_features.unsqueeze(1).repeat(1, temporal_embedding.shape[0], 1) ## Look Module - Lidar lidar_attn_weight = self.lidar_look_module_atten(torch.cat([current_wp, current_ctrl_softplus, temporal_embedding.unsqueeze(0).repeat(current_wp.shape[0], 1, 1)], dim=-1)) ## Different feature maps for different control signals and time-steps temporal_lidar_feat = lidar_attn_weight.unsqueeze(-1).unsqueeze(-1) * lidar_feat_with_high_resolution.unsqueeze(1).float() ## Retrieve Lidar features lidar_look_features = self.obtain_lidar_look_features(current_wp, temporal_lidar_feat) lidar_look_features = self.lidar_look_module_MLP(lidar_look_features) look_features = torch.cat([img_look_features, torch.zeros_like(lidar_look_features)], dim=-1) return look_features class ThinkTwiceDecoderLayer(nn.Module): def __init__(self, act): super().__init__() self.act = act self.prediction_module = PredictionModule(self.act) self.look_module = LookModule(self.act) self.mlp = nn.Sequential( nn.LayerNorm(256+128+512+128), ## flattened prediction BEV feat 256 + look feature 512 + temporal embedding 128 + measurement nn.Linear(256+128+512+128, 512), self.act(), nn.Dropout(0.0), nn.Linear(512, 512), self.act(), ) self.traj_offset_module = nn.Sequential( nn.Linear(512+2, 256), self.act(), nn.Linear(256, 64), self.act(), nn.Linear(64, 2), ) self.ctrl_offset_module = nn.Sequential( nn.Linear(512+4, 256), self.act(), nn.Linear(256, 64), self.act(), nn.Linear(64, 4), ) self.BEV_feat_update_module = nn.Sequential( nn.Conv2d(512*4+32, 128, kernel_size=3, padding=1), self.act(), nn.Conv2d(128, 32, kernel_size=3, padding=1), ) self.flattened_BEV_feat_update_module = nn.Sequential( nn.Linear(256+512*4, 512), self.act(), nn.Linear(512, 256), ) self.fp16_enabled = False @force_fp32() def forward(self, BEV_feat, current_wp, current_ctrl, future_bev_feat_from_last_layer, parent_module, grid2feat, measurement_feat, flattened_BEV_feat, coor2img, img_size, mlvl_feats, fpn_feat_flatten, spatial_shapes, level_start_index, lidar_feat_with_high_resolution, temporal_embedding, static_embedding): current_ctrl_softplus = F.softplus(current_ctrl) ## Prediction Module future_bev_feat = self.prediction_module(current_BEV_feature=BEV_feat, current_wp=current_wp, current_ctrl=current_ctrl_softplus, future_bev_feat_from_last_layer=future_bev_feat_from_last_layer) flattened_future_BEV_feat, _ = grid2feat(future_bev_feat, parent_module) flattened_future_BEV_feat = flattened_future_BEV_feat.view(BEV_feat.shape[0], 4, 256) ## Pred_len = 4 future_bev_feat = future_bev_feat.view(BEV_feat.shape[0], -1, BEV_feat.shape[1], BEV_feat.shape[2], BEV_feat.shape[3]) ## Look Module look_features = self.look_module( current_wp=current_wp, current_ctrl_softplus=current_ctrl_softplus, measurement_feat=measurement_feat, flattened_feat=flattened_BEV_feat, coor2img=coor2img, img_size=img_size, mlvl_feats=mlvl_feats, fpn_feat_flatten=fpn_feat_flatten, spatial_shapes=spatial_shapes, level_start_index=level_start_index, lidar_feat_with_high_resolution=lidar_feat_with_high_resolution, temporal_embedding=temporal_embedding, static_embedding=static_embedding ) all_future_feat = self.mlp(torch.cat([flattened_future_BEV_feat, look_features, temporal_embedding.unsqueeze(0).repeat(flattened_future_BEV_feat.shape[0], 1, 1), measurement_feat.unsqueeze(1).repeat(1, flattened_future_BEV_feat.shape[1], 1)], dim=-1)) traj_offset =self.traj_offset_module(torch.cat([current_wp, all_future_feat], dim=-1)) ctrl_offset = self.ctrl_offset_module(torch.cat([current_ctrl, all_future_feat], dim=-1)) ## Residual update of feature maps similar to DETR updated_BEV_feat = self.BEV_feat_update_module(torch.cat([BEV_feat, all_future_feat.view(BEV_feat.shape[0], -1).unsqueeze(-1).unsqueeze(-1).repeat(1, 1, BEV_feat.shape[2], BEV_feat.shape[3])], dim=1)) + BEV_feat updated_flattend_BEV_feat = self.flattened_BEV_feat_update_module(torch.cat([flattened_BEV_feat, all_future_feat.view(flattened_BEV_feat.shape[0], -1)], dim=-1)) + flattened_BEV_feat return traj_offset, ctrl_offset, future_bev_feat, updated_BEV_feat, updated_flattend_BEV_feat @HEADS.register_module() class ThinkTwiceDecoder(BaseModule): def __init__(self, *args, config=None, bev_h=None, bev_w=None, BEV_feat_dim=256, ## BEVfFeature dimension flattened_BEV_feat_dim=256, ## Flattened 1D feature dimension **kwargs): super(ThinkTwiceDecoder, self).__init__( *args, **kwargs) self.config = config self.bev_h = bev_h self.bev_w = bev_w self.BEV_feat_dim = BEV_feat_dim self.flattened_BEV_feat_dim = flattened_BEV_feat_dim self.act = nn.ReLU #For distil self.distil_index = [2, 3, 4, 5] ## All layers self.distil_kl_loss_weight_dict = {2:0.25, 3:1.0/3.0, 4:1.0/4.0, 5:1/11.0} self.wp_loss_weight = 15.0 self.action_loss_weight = 15.0 self.build_layers() self.fp16_enabled = False def build_layers(self): self.build_coarse_output_layer() self.build_refine_layers() self.apply(init_weights) ## Similar to TCP, give 1D feature map, predict 1D traj and control def build_coarse_output_layer(self): self.join_traj = nn.Sequential( nn.Linear(128+self.flattened_BEV_feat_dim, 512), self.act(), nn.Linear(512, 512), self.act(), nn.Linear(512, 256), self.act(), ) self.output_traj = nn.Sequential( nn.Linear(256, 512), self.act(), nn.Linear(512, 2*self.config.pred_len), ) self.join_ctrl = nn.Sequential( nn.Linear(128+self.flattened_BEV_feat_dim, 512), self.act(), nn.Linear(512, 512), self.act(), nn.Linear(512, 256), self.act(), ) self.speed_branch = nn.Sequential( nn.Linear(self.flattened_BEV_feat_dim, 256), self.act(), nn.Linear(256, 256), self.act(), nn.Linear(256, 1), ) self.value_branch_traj = nn.Sequential( nn.Linear(256, 256), self.act(), nn.Linear(256, 256), self.act(), nn.Linear(256, 1), ) self.value_branch_ctrl = nn.Sequential( nn.Linear(256, 256), self.act(), nn.Linear(256, 256), self.act(), nn.Linear(256, 1), ) # shared branches_neurons self.dim_out = 2 self.policy_head = nn.Sequential( nn.Linear(256, 512), self.act(), nn.Linear(512, 512), self.act(), ) self.dist_mu = nn.Sequential( nn.Linear(512, 512), self.act(), nn.Linear(512, self.dim_out * self.config.pred_len), ) ## No softplus here! self.dist_sigma = nn.Sequential( nn.Linear(512, 512), self.act(), nn.Linear(512, self.dim_out * self.config.pred_len), ) ## No softplus here! def build_refine_layers(self): ## Transform all FPN feature to the same dimension to conduct multi-scale deformable attention self.fpn_linear0 = nn.Conv2d(in_channels=self.config["FPN_out_channels"][0], out_channels=256, kernel_size=1) self.fpn_linear1 = nn.Conv2d(in_channels=self.config["FPN_out_channels"][1], out_channels=256, kernel_size=1) self.fpn_linear2 = nn.Conv2d(in_channels=self.config["FPN_out_channels"][2], out_channels=256, kernel_size=1) self.fpn_linear3 = nn.Conv2d(in_channels=self.config["FPN_out_channels"][3], out_channels=256, kernel_size=1) self.temporal_embedding = nn.parameter.Parameter(torch.zeros(self.config.pred_len, 128)) ## Embedding for different predicted time-step self.cams_embeds = nn.parameter.Parameter(torch.zeros(4, 256)) self.static_embedding = nn.parameter.Parameter(torch.zeros(4, 128)) self.level_embeds = nn.parameter.Parameter(torch.zeros(4, 256)) ## For multi-scale attention nn.init.trunc_normal_(self.temporal_embedding, mean=0, std=0.02) nn.init.trunc_normal_(self.cams_embeds, mean=0, std=0.02) nn.init.trunc_normal_(self.static_embedding, mean=0, std=0.02) nn.init.trunc_normal_(self.temporal_embedding, mean=0, std=0.02) self.decoder_layers = nn.ModuleList([ThinkTwiceDecoderLayer(self.act) for _ in range(self.config["refine_num"])]) @force_fp32() def transform_fpn_feats(self, mlvl_feats): spatial_shapes = [] feat_flatten = [] """ flatten feats of each level """ for lvl, feat in enumerate(mlvl_feats): bs_num_cam, c, h, w = feat.shape num_cam = 4 bs = int(bs_num_cam/num_cam) feat = feat.view(bs, num_cam, c, h, w) spatial_shape = (h, w) feat = feat.flatten(3).permute(1, 0, 3, 2) feat = feat + self.cams_embeds[:, None, None, :].to(feat.dtype) feat = feat + self.level_embeds[None, None, lvl:lvl + 1, :].to(feat.dtype) spatial_shapes.append(spatial_shape) feat_flatten.append(feat) """ concat flattened features """ feat_flatten = torch.cat(feat_flatten, 2) # (cam, bs, sum(h*w), 256) spatial_shapes = torch.as_tensor(spatial_shapes, dtype=torch.long, device=mlvl_feats[0].device) level_start_index = torch.cat((spatial_shapes.new_zeros((1,)), spatial_shapes.prod(1).cumsum(0)[:-1])) fpn_feat_flatten = feat_flatten.permute(0, 2, 1, 3) # (num_cam, sum(H*W), bs, embed_dims) return spatial_shapes, level_start_index, fpn_feat_flatten ## Convert 32x21x21 BEV feature to 256 dim 1D feature by the shared flatten module @auto_fp16() def grid2feat(self, grid_feat, parent_module): mid_feature = [None, None] #Currently no feature for 8x94x94 16x45x45 mid_feature.append(grid_feat) feats64_10_10 = parent_module.MLP10(parent_module.inplace_act(parent_module.conv21_10(grid_feat))) mid_feature.append(feats64_10_10) feats128_4_4 = parent_module.MLP4(parent_module.inplace_act(parent_module.conv10_4(feats64_10_10))) mid_feature.append(feats128_4_4) feats256_2_2 = parent_module.MLP2(parent_module.inplace_act(parent_module.conv4_2((feats128_4_4)))) mid_feature.append(feats256_2_2) flattened_BEV_feat = parent_module.output_fc(feats256_2_2.flatten(start_dim=1)) return flattened_BEV_feat, mid_feature @force_fp32() def forward(self, flattend_BEV_feat, BEV_feat, measurement_feat, target_point, parent_module, teacher_forcing_data=None, look_feature_metadata=None): outs = {} outs['bev_feature'] = BEV_feat ## Coarase prediction similar to TCP ### Predict speed by sensor feature to alleviate copy cat problem outs['pred_speed'] = self.speed_branch(flattend_BEV_feat) ### Coarse Traj Branch j_traj = self.join_traj(torch.cat([flattend_BEV_feat, measurement_feat], 1)) outs['pred_value_traj'] = self.value_branch_traj(j_traj) outs['pred_features_traj'] = j_traj pred_wp = self.output_traj(j_traj).view(-1, self.config.pred_len, 2) pred_wp_lis = [pred_wp] ### Coarse Ctrl Branch j_ctrl = self.join_ctrl(torch.cat([flattend_BEV_feat, measurement_feat], dim=-1)) outs['pred_value_ctrl'] = self.value_branch_ctrl(j_ctrl) outs['pred_features_ctrl'] = j_ctrl policy = self.policy_head(j_ctrl) predicted_mu = self.dist_mu(policy).view(-1, self.config.pred_len, self.dim_out) predicted_sigma = self.dist_sigma(policy).view(-1, self.config.pred_len, self.dim_out) pred_ctrl_lis = [torch.cat([predicted_mu, predicted_sigma], dim=-1)] ## Look Module ### Prepare features for Look Module - Image lidar2img = look_feature_metadata[0].to(flattend_BEV_feat.device) ida_mat = look_feature_metadata[1].to(flattend_BEV_feat.device) fpn_feats = look_feature_metadata[2] mlvl_feats = [] mlvl_feats.append(self.fpn_linear0(fpn_feats[0])) mlvl_feats.append(self.fpn_linear1(fpn_feats[1])) mlvl_feats.append(self.fpn_linear2(fpn_feats[2])) mlvl_feats.append(self.fpn_linear3(fpn_feats[3])) spatial_shapes, level_start_index, fpn_feat_flatten = self.transform_fpn_feats(mlvl_feats) ### Prepare features for Look Module - Lidar lidar_feat_with_high_resolution = look_feature_metadata[3] future_bev_feat = None current_BEV_feat = BEV_feat.clone() current_flattened_BEV_feat = flattend_BEV_feat.clone() stored_BEV_feat = [] stored_flattened_BEV_feat = [] stored_future_BEV_feat = [] for refine_layer_index in range(self.config["refine_num"]): current_wp = pred_wp_lis[-1].detach() current_ctrl = pred_ctrl_lis[-1].detach() traj_offset, ctrl_offset, updated_future_bev_feat, updated_BEV_feat, updated_flattend_BEV_feat = self.decoder_layers[refine_layer_index](BEV_feat=current_BEV_feat, current_wp=current_wp, current_ctrl=current_ctrl, future_bev_feat_from_last_layer=future_bev_feat, parent_module=parent_module, grid2feat=self.grid2feat, measurement_feat=measurement_feat, flattened_BEV_feat=current_flattened_BEV_feat, coor2img=[lidar2img, ida_mat], img_size=self.config["img_size"], mlvl_feats=mlvl_feats, fpn_feat_flatten=fpn_feat_flatten, spatial_shapes=spatial_shapes, level_start_index=level_start_index, lidar_feat_with_high_resolution=lidar_feat_with_high_resolution, temporal_embedding=self.temporal_embedding, static_embedding=self.static_embedding) pred_wp_lis.append(traj_offset.float()+current_wp.float()) pred_ctrl_lis.append(ctrl_offset.float()+current_ctrl.float()) stored_BEV_feat.append(updated_BEV_feat) current_BEV_feat = updated_BEV_feat stored_flattened_BEV_feat.append(updated_flattend_BEV_feat) current_flattened_BEV_feat = updated_flattend_BEV_feat stored_future_BEV_feat.append(updated_future_bev_feat) future_bev_feat = updated_future_bev_feat outs["refine_flattned_BEV_feature"] = torch.stack(stored_flattened_BEV_feat, dim=1) outs["refine_BEV_feature"] = torch.stack(stored_BEV_feat, dim=1) outs["refine_future_BEV_feature"] = torch.stack(stored_future_BEV_feat, dim=1).view(current_wp.shape[0], current_wp.shape[1], self.config["refine_num"], 32, 21, 21).transpose(1, 2) pred_wp_lis = torch.stack(pred_wp_lis, dim=1) #BxrefinexTx2 pred_ctrl_lis = torch.clamp(F.softplus(torch.stack(pred_ctrl_lis, dim=1).float()), min=1e-3) #BxrefinexTx4 outs['pred_wp'] = pred_wp_lis outs['mu_branches'] = pred_ctrl_lis[:, :, 0, :2] outs['sigma_branches'] = pred_ctrl_lis[:, :, 0, 2:] outs['future_mu'] = pred_ctrl_lis[:, :, 1:, :2] outs['future_sigma'] = pred_ctrl_lis[:, :, 1:, 2:] ## Apply teacher forcing if teacher_forcing_data is not None: teacher_pred_traj_offset_lis = [] teacher_pred_ctrl_offset_lis = [] ##GT input should obtain GT future feature current_wp = teacher_forcing_data["waypoints"].float() current_ctrl_softplus = torch.cat([torch.cat([teacher_forcing_data["action_mu"], teacher_forcing_data["action_sigma"]], dim=-1).unsqueeze(1), torch.cat([torch.stack(teacher_forcing_data["future_action_mu"][:-1], dim=1), torch.stack(teacher_forcing_data["future_action_sigma"][:-1], dim=1)], dim=-1)], dim=1).float() current_ctrl = inv_softplus(current_ctrl_softplus) future_bev_feat = None current_BEV_feat = BEV_feat.clone() current_flattened_BEV_feat = flattend_BEV_feat.clone() stored_BEV_feat = [] stored_flattened_BEV_feat = [] stored_future_BEV_feat = [] for refine_layer_index in range(self.config["refine_num"]): traj_offset, ctrl_offset, updated_future_bev_feat, updated_BEV_feat, updated_flattend_BEV_feat = self.decoder_layers[refine_layer_index](BEV_feat=current_BEV_feat, current_wp=current_wp, current_ctrl=current_ctrl, future_bev_feat_from_last_layer=future_bev_feat, parent_module=parent_module, grid2feat=self.grid2feat, measurement_feat=measurement_feat, flattened_BEV_feat=current_flattened_BEV_feat, coor2img=[lidar2img, ida_mat], img_size=self.config["img_size"], mlvl_feats=mlvl_feats, fpn_feat_flatten=fpn_feat_flatten, spatial_shapes=spatial_shapes, level_start_index=level_start_index, lidar_feat_with_high_resolution=lidar_feat_with_high_resolution, temporal_embedding=self.temporal_embedding, static_embedding=self.static_embedding) teacher_pred_traj_offset_lis.append(traj_offset) teacher_pred_ctrl_offset_lis.append(ctrl_offset) stored_BEV_feat.append(updated_BEV_feat) current_BEV_feat = updated_BEV_feat stored_flattened_BEV_feat.append(updated_flattend_BEV_feat) current_flattened_BEV_feat = updated_flattend_BEV_feat stored_future_BEV_feat.append(updated_future_bev_feat) future_bev_feat = updated_future_bev_feat teacher_pred_traj_offset_lis = torch.stack(teacher_pred_traj_offset_lis, dim=1) teacher_pred_ctrl_offset_lis = torch.stack(teacher_pred_ctrl_offset_lis, dim=1) teacher_future_BEV_lis = torch.stack(stored_future_BEV_feat, dim=1) outs["teacher_pred_wp_offset"] = teacher_pred_traj_offset_lis outs["teacher_pred_ctrl_offset_lis"] = teacher_pred_ctrl_offset_lis outs["teacher_future_BEV_feature"] = teacher_future_BEV_lis outs["teacher_refine_flattned_BEV_feature"] = torch.stack(stored_flattened_BEV_feat, dim=1) outs["teacher_refine_BEV_feature"] = torch.stack(stored_BEV_feat, dim=1) return outs @force_fp32() def loss(self, batch, pred, mid_BEV_feature, indices_with_gradient=None, ): loss_dict = dict() gt_speed = batch['speed'].to(dtype=torch.float32).view(-1,1) / 12. gt_value = batch['value'].view(-1,1) gt_flattened_BEV_feature = batch['feature'] gt_waypoints = batch['waypoints'] ## Open Loop Statistics with torch.no_grad(): pred_action = self._get_action_beta(pred['mu_branches'][:, -1, :], pred['sigma_branches'][:, -1, :]) gt_action = self._get_action_beta(batch['action_mu'], batch['action_sigma']) l1_action = F.l1_loss(pred_action, gt_action, reduction="none").detach().mean(dim=0) loss_dict["current_throttle_brake_offset"] = l1_action[0] loss_dict['current_steer_offset'] = l1_action[1] wp_offset = F.l1_loss(pred['pred_wp'][:, -1, :, :], gt_waypoints[:, :, :],reduction="none").detach().mean(dim=0) mean_wp_offset = wp_offset.mean(dim=0) loss_dict["longitudinal_offset"] = mean_wp_offset[0] loss_dict["lateral_offset"] = mean_wp_offset[1] loss_dict["longitudinal_offset"] = mean_wp_offset[0] loss_dict["lateral_offset"] = mean_wp_offset[1] ## Current Action Loss gt_ctrl_distribution = Beta(batch['action_mu'].unsqueeze(1), batch['action_sigma'].unsqueeze(1)) pred_ctrl_disttribution = Beta(pred['mu_branches'], pred['sigma_branches']) kl_div = torch.distributions.kl_divergence(gt_ctrl_distribution, pred_ctrl_disttribution) loss_dict['action_loss'] = kl_div.mean() * self.action_loss_weight loss_dict['speed_loss'] = F.smooth_l1_loss(pred['pred_speed'], gt_speed, reduction="mean") loss_dict['value_loss'] = (F.smooth_l1_loss(pred['pred_value_traj'], gt_value, reduction="mean") + F.smooth_l1_loss(pred['pred_value_ctrl'], gt_value, reduction="none")) * self.config.value_weight loss_dict['flattened_feature_loss'] = (F.smooth_l1_loss(pred['pred_features_traj'], gt_flattened_BEV_feature, reduction="mean") + F.smooth_l1_loss(pred['pred_features_ctrl'], gt_flattened_BEV_feature, reduction="mean")) * self.config.features_weight ## Future Action Loss gt_future_action_mu = torch.stack(batch['future_action_mu'][:-1], axis=1).unsqueeze(1) gt_future_action_sigma = torch.stack(batch['future_action_sigma'][:-1], axis=1).unsqueeze(1) gt_future_ctrl_distribution = Beta(gt_future_action_mu, gt_future_action_sigma) pred_future_ctrl_distribution = Beta(pred['future_mu'], pred['future_sigma']) future_kl_div = torch.distributions.kl_divergence(gt_future_ctrl_distribution, pred_future_ctrl_distribution) loss_dict['future_action_loss'] = future_kl_div.mean() * self.action_loss_weight * 0.25 ## Traj Loss wp_loss = F.smooth_l1_loss(pred['pred_wp'], gt_waypoints.unsqueeze(1).repeat(1, pred['pred_wp'].shape[1], 1, 1), reduction="mean") loss_dict['wp_loss'] = wp_loss * self.wp_loss_weight ## Feature Disillation Loss ## BEV Feature Loss of Encoder for feature_map_index in self.distil_index: gt_BEV_feature = batch["grid_feature"][feature_map_index] pred_BEV_feature = mid_BEV_feature[feature_map_index] loss_dict['BEV_feature_loss'+str(feature_map_index)] = torch.clamp(F.smooth_l1_loss(pred_BEV_feature, gt_BEV_feature, reduction="none"), min=-5.0, max=5.0).mean() * self.distil_kl_loss_weight_dict[feature_map_index] ## BEV Feature Loss of Look Module pred_BEV_feature = pred["refine_BEV_feature"] gt_BEV_feature = batch["grid_feature"][2].unsqueeze(1).repeat(1, pred_BEV_feature.shape[1], 1, 1, 1) ## 21x21 BEV feature map loss_dict['refine_BEV_feature_loss2'] = torch.clamp(F.smooth_l1_loss(pred_BEV_feature, gt_BEV_feature, reduction="none"), min=-5.0, max=5.0).mean() * self.distil_kl_loss_weight_dict[2] loss_dict['refine_flattened_feature_loss'] = torch.clamp(F.smooth_l1_loss(pred['refine_flattned_BEV_feature'], gt_flattened_BEV_feature.unsqueeze(1).repeat(1, pred['refine_flattned_BEV_feature'].shape[1], 1), reduction="none"), min=-5.0, max=5.0).mean() * self.config.features_weight * 0.1 # Teacher Forcing Part ## All offset should be zero loss_dict['teacher_wp_loss'] = F.smooth_l1_loss(pred['teacher_pred_wp_offset'], torch.zeros_like(pred['teacher_pred_wp_offset']), reduction='mean') loss_dict['teacher_action_loss'] = F.smooth_l1_loss(pred['teacher_pred_ctrl_offset_lis'], torch.zeros_like(pred['teacher_pred_ctrl_offset_lis']), reduction='mean') ## Future Feature Supervision feature_map_index = 2 ## 21x21 feature map gt_future_BEV_feature = torch.stack([_[feature_map_index] for _ in batch["future_grid_feature"]], dim=1) pred_future_BEV_feature = pred["teacher_future_BEV_feature"] ## NumSamples, RefineNum, TemporalStep, Channel, Width, Height N,R,T,C,W,H = pred_future_BEV_feature.shape gt_future_BEV_feature = gt_future_BEV_feature.unsqueeze(1).repeat(1, R, 1, 1, 1, 1) loss_dict['teacher_future_BEV_feature_loss'+str(feature_map_index)] = torch.clamp(F.smooth_l1_loss(pred_future_BEV_feature, gt_future_BEV_feature, reduction="none"), min=-5.0, max=5.0).mean() * self.distil_kl_loss_weight_dict[2] ## BEV Feature Loss of Look Module pred_BEV_feature = pred["teacher_refine_BEV_feature"] gt_BEV_feature = batch["grid_feature"][2].unsqueeze(1).repeat(1, pred_BEV_feature.shape[1], 1, 1, 1) ## 21x21 BEV feature map loss_dict['teacher_refine_BEV_feature_loss'+str(feature_map_index)] = torch.clamp(F.smooth_l1_loss(pred_BEV_feature, gt_BEV_feature, reduction="none"), min=-5.0, max=5.0).mean() * self.distil_kl_loss_weight_dict[2] loss_dict['teacher_refine_flattened_feature_loss'] = torch.clamp(F.smooth_l1_loss(pred['teacher_refine_flattned_BEV_feature'], gt_flattened_BEV_feature.unsqueeze(1).repeat(1, pred['teacher_refine_flattned_BEV_feature'].shape[1], 1), reduction="none"), min=-5.0, max=5.0).mean() * self.config.features_weight return loss_dict @force_fp32() def _get_action_beta(self, alpha, beta): x = torch.zeros_like(alpha) x[:, 1] += 0.5 mask1 = (alpha > 1) & (beta > 1) x[mask1] = (alpha[mask1]-1)/(alpha[mask1]+beta[mask1]-2) mask2 = (alpha <= 1) & (beta > 1) x[mask2] = 0.0 mask3 = (alpha > 1) & (beta <= 1) x[mask3] = 1.0 # mean mask4 = (alpha <= 1) & (beta <= 1) x[mask4] = alpha[mask4]/torch.clamp((alpha[mask4]+beta[mask4]), min=1e-5) x = x * 2 - 1 return x ================================================ FILE: open_loop_training/code/model_code/dense_heads/utils.py ================================================ import torch import torch.nn as nn import torch.nn.functional as F def sigmoid_focal_loss( inputs: torch.Tensor, targets: torch.Tensor, alpha: float = 0.25, gamma: float = 2, reduction: str = "none", ) -> torch.Tensor: p = torch.sigmoid(inputs) ce_loss = F.binary_cross_entropy_with_logits(inputs, targets, reduction="none") p_t = p * targets + (1 - p) * (1 - targets) loss = ce_loss * ((1 - p_t) ** gamma) if alpha >= 0: alpha_t = alpha * targets + (1 - alpha) * (1 - targets) loss = alpha_t * loss if reduction == "mean": loss = loss.mean() elif reduction == "sum": loss = loss.sum() return loss def init_weights(m): with torch.no_grad(): classname = m.__class__.__name__ if classname.find('Conv2d') != -1: nn.init.xavier_normal_(m.weight) if m.bias is not None: nn.init.constant_(m.bias, 0) elif classname.find('LayerNorm') != -1: nn.init.constant_(m.weight, 1) nn.init.constant_(m.bias, 0) elif classname.find('BatchNorm') != -1: nn.init.constant_(m.weight, 1) nn.init.constant_(m.bias, 0) elif classname.find('GroupNorm') != -1: nn.init.constant_(m.weight, 1) nn.init.constant_(m.bias, 0) elif classname.find('Linear') != -1: if m.bias is not None: nn.init.constant_(m.bias, 0) nn.init.xavier_normal_(m.weight) elif classname.find('Embedding') != -1: nn.init.trunc_normal_(m.weight, mean=0, std=0.02) class SpatialGRU(nn.Module): """A GRU cell that takes an input tensor [BxTxCxHxW] and an optional previous state and passes a convolutional gated recurrent unit over the data""" def __init__(self, input_size, hidden_size, act, gru_bias_init=0.0): super().__init__() self.input_size = input_size self.hidden_size = hidden_size self.gru_bias_init = gru_bias_init self.act = act self.conv_update = nn.Sequential( nn.Conv2d(input_size + hidden_size, hidden_size, kernel_size=3, bias=True, padding=1), self.act(), nn.Conv2d(hidden_size, hidden_size, kernel_size=3, bias=True, padding=1) ) self.conv_reset = nn.Sequential( nn.Conv2d(input_size + hidden_size, hidden_size, kernel_size=3, bias=True, padding=1), self.act(), nn.Conv2d(hidden_size, hidden_size, kernel_size=3, bias=True, padding=1) ) self.conv_state_tilde = nn.Sequential( nn.Conv2d(input_size + hidden_size, hidden_size, kernel_size=3, bias=True, padding=1), self.act(), nn.Conv2d(hidden_size, hidden_size, kernel_size=3, bias=True, padding=1) ) self.conv_decoder = nn.Sequential( nn.Conv2d(hidden_size, hidden_size, kernel_size=3, bias=True, padding=1), self.act(), nn.Conv2d(hidden_size, hidden_size, kernel_size=3, bias=True, padding=1) ) def forward(self, x, state=None): # Check size assert len(x.size()) == 5, 'Input tensor must be BxTxCxHxW.' # recurrent layers rnn_output = [] b, timesteps, c, h, w = x.size() rnn_state = torch.zeros(b, self.hidden_size, h, w, device=x.device) if state is None else state for t in range(timesteps): x_t = x[:, t] rnn_state = self.gru_cell(x_t, rnn_state) rnn_output.append(self.conv_decoder(rnn_state)) # reshape rnn output to batch tensor return torch.stack(rnn_output, dim=1) def gru_cell(self, x, state): # Compute gates x_and_state = torch.cat([x, state], dim=1) update_gate = self.conv_update(x_and_state) reset_gate = self.conv_reset(x_and_state) # Add bias to initialise gate as close to identity function update_gate = torch.sigmoid(update_gate + self.gru_bias_init) reset_gate = torch.sigmoid(reset_gate + self.gru_bias_init) # Compute proposal state, activation is defined in norm_act_config (can be tanh, ReLU etc) state_tilde = self.conv_state_tilde(torch.cat([x, (1.0 - reset_gate) * state], dim=1)) output = (1.0 - update_gate) * state + update_gate * state_tilde return output ================================================ FILE: open_loop_training/code/utils.py ================================================ from collections import deque import torch import torch.nn as nn import numpy as np from mmcv.runner import force_fp32, auto_fp16 class PIDController(object): def __init__(self, K_P=1.0, K_I=0.0, K_D=0.0, n=20): self._K_P = K_P self._K_I = K_I self._K_D = K_D self._window = deque([0 for _ in range(n)], maxlen=n) self._max = 0.0 self._min = 0.0 def step(self, error): self._window.append(error) self._max = max(self._max, abs(error)) self._min = -abs(self._max) if len(self._window) >= 2: integral = np.mean(self._window) derivative = (self._window[-1] - self._window[-2]) else: integral = 0.0 derivative = 0.0 return self._K_P * error + self._K_I * integral + self._K_D * derivative class FocalLoss(nn.Module): def __init__(self, alpha=0.5, gamma=2, weight=None, ignore_index=255): super().__init__() self.alpha = alpha self.gamma = gamma self.weight = weight self.ignore_index = ignore_index self.ce_fn = nn.CrossEntropyLoss(weight=self.weight, ignore_index=self.ignore_index) self.fp16_enabled = False @force_fp32() def forward(self, preds, labels): logpt = -self.ce_fn(preds.float(), labels) pt = torch.exp(logpt) loss = -((1 - pt) ** self.gamma) * self.alpha * logpt return loss def set_dropout_zero(m): with torch.no_grad(): classname = m.__class__.__name__ if classname.find('Dropout') != -1 or classname.find('Dropout2d') != -1: m.p = 0 elif classname.find('DropPath') != -1: m.drop_prob = 0 def init_weights(m): with torch.no_grad(): classname = m.__class__.__name__ if classname.find('Conv2d') != -1: nn.init.xavier_normal_(m.weight) if m.bias is not None: nn.init.constant_(m.bias, 0) elif classname.find('LayerNorm') != -1: nn.init.constant_(m.weight, 1) nn.init.constant_(m.bias, 0) elif classname.find('BatchNorm') != -1: nn.init.constant_(m.weight, 1) nn.init.constant_(m.bias, 0) elif classname.find('GroupNorm') != -1: nn.init.constant_(m.weight, 1) nn.init.constant_(m.bias, 0) elif classname.find('Linear') != -1: if m.bias is not None: nn.init.constant_(m.bias, 0) nn.init.xavier_normal_(m.weight) elif classname.find('Embedding') != -1: nn.init.trunc_normal_(m.weight, mean=0, std=0.02) class SEModule(nn.Module): def __init__(self, channels, act): super(SEModule, self).__init__() self.fc1 = nn.Conv2d(channels, channels, kernel_size=1) self.act = act() self.fc2 = nn.Conv2d(channels, channels, kernel_size=1) def forward(self, x): x_se = x.mean((2, 3), keepdim=True) x_se = 0.5 * x_se + 0.5 * x.amax((2, 3), keepdim=True) x_se = self.fc1(x_se) x_se = self.act(x_se) x_se = self.fc2(x_se) return x * x_se.sigmoid() class SEBasicBlock(nn.Module): def __init__(self, inplanes, act): super(SEBasicBlock, self).__init__() self.conv1 = nn.Conv2d(inplanes, inplanes * 2, kernel_size=3, padding=1,) self.bn1 = nn.BatchNorm2d(inplanes * 2) self.act1 = act() self.conv2 = nn.Conv2d(inplanes*2, inplanes, kernel_size=3, padding=1,) self.bn2 = nn.BatchNorm2d(inplanes) self.act2 = act() self.se = SEModule(inplanes, act) self.act3 = act() def forward(self, x): shortcut = x x = self.conv1(x) x = self.bn1(x) x = self.act1(x) x = self.conv2(x) x = self.bn2(x) x = self.act2(x) x = self.se(x) x += shortcut x = self.act3(x) return x ================================================ FILE: open_loop_training/configs/_base_/default_runtime.py ================================================ checkpoint_config = dict(interval=1) # yapf:disable push # By default we use textlogger hook and tensorboard # For more loggers see # https://mmcv.readthedocs.io/en/latest/api.html#mmcv.runner.LoggerHook log_config = dict( interval=50, hooks=[ dict(type='TextLoggerHook'), dict(type='TensorboardLoggerHook') ]) # yapf:enable dist_params = dict(backend='nccl') log_level = 'INFO' work_dir = None load_from = None resume_from = None workflow = [('train', 1)] custom_hooks = [dict(type="MySetEpochInfoHook")] ================================================ FILE: open_loop_training/configs/_base_/schedules/cosine.py ================================================ # This schedule is mainly used by models with dynamic voxelization # optimizer lr = 0.003 # max learning rate optimizer = dict( type='AdamW', lr=lr, betas=(0.95, 0.99), # the momentum is change during training weight_decay=0.001) optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2)) lr_config = dict( policy='CosineAnnealing', warmup='linear', warmup_iters=1000, warmup_ratio=1.0 / 10, min_lr_ratio=1e-5) momentum_config = None runner = dict(type='EpochBasedRunner', max_epochs=40) ================================================ FILE: open_loop_training/configs/_base_/schedules/cyclic_20e.py ================================================ # For nuScenes dataset, we usually evaluate the model at the end of training. # Since the models are trained by 24 epochs by default, we set evaluation # interval to be 20. Please change the interval accordingly if you do not # use a default schedule. # optimizer # This schedule is mainly used by models on nuScenes dataset optimizer = dict(type='AdamW', lr=1e-4, weight_decay=0.01) # max_norm=10 is better for SECOND optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2)) lr_config = dict( policy='cyclic', target_ratio=(10, 1e-4), cyclic_times=1, step_ratio_up=0.4, ) momentum_config = dict( policy='cyclic', target_ratio=(0.85 / 0.95, 1), cyclic_times=1, step_ratio_up=0.4, ) # runtime settings runner = dict(type='EpochBasedRunner', max_epochs=20) ================================================ FILE: open_loop_training/configs/_base_/schedules/cyclic_40e.py ================================================ # The schedule is usually used by models trained on KITTI dataset # The learning rate set in the cyclic schedule is the initial learning rate # rather than the max learning rate. Since the target_ratio is (10, 1e-4), # the learning rate will change from 0.0018 to 0.018, than go to 0.0018*1e-4 lr = 0.0018 # The optimizer follows the setting in SECOND.Pytorch, but here we use # the offcial AdamW optimizer implemented by PyTorch. optimizer = dict(type='AdamW', lr=lr, betas=(0.95, 0.99), weight_decay=0.01) optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2)) # We use cyclic learning rate and momentum schedule following SECOND.Pytorch # https://github.com/traveller59/second.pytorch/blob/3aba19c9688274f75ebb5e576f65cfe54773c021/torchplus/train/learning_schedules_fastai.py#L69 # noqa # We implement them in mmcv, for more details, please refer to # https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/lr_updater.py#L327 # noqa # https://github.com/open-mmlab/mmcv/blob/f48241a65aebfe07db122e9db320c31b685dc674/mmcv/runner/hooks/momentum_updater.py#L130 # noqa lr_config = dict( policy='cyclic', target_ratio=(10, 1e-4), cyclic_times=1, step_ratio_up=0.4, ) momentum_config = dict( policy='cyclic', target_ratio=(0.85 / 0.95, 1), cyclic_times=1, step_ratio_up=0.4, ) # Although the max_epochs is 40, this schedule is usually used we # RepeatDataset with repeat ratio N, thus the actual max epoch # number could be Nx40 runner = dict(type='EpochBasedRunner', max_epochs=40) ================================================ FILE: open_loop_training/configs/_base_/schedules/mmdet_schedule_1x.py ================================================ # optimizer optimizer = dict(type='SGD', lr=0.02, momentum=0.9, weight_decay=0.0001) optimizer_config = dict(grad_clip=None) # learning policy lr_config = dict( policy='step', warmup='linear', warmup_iters=500, warmup_ratio=0.001, step=[8, 11]) runner = dict(type='EpochBasedRunner', max_epochs=12) ================================================ FILE: open_loop_training/configs/_base_/schedules/schedule_2x.py ================================================ # optimizer # This schedule is mainly used by models on nuScenes dataset optimizer = dict(type='AdamW', lr=0.001, weight_decay=0.01) # max_norm=10 is better for SECOND optimizer_config = dict(grad_clip=dict(max_norm=35, norm_type=2)) lr_config = dict( policy='step', warmup='linear', warmup_iters=1000, warmup_ratio=1.0 / 1000, step=[20, 23]) momentum_config = None # runtime settings runner = dict(type='EpochBasedRunner', max_epochs=24) ================================================ FILE: open_loop_training/configs/_base_/schedules/schedule_3x.py ================================================ # optimizer # This schedule is mainly used by models on indoor dataset, # e.g., VoteNet on SUNRGBD and ScanNet lr = 0.008 # max learning rate optimizer = dict(type='AdamW', lr=lr, weight_decay=0.01) optimizer_config = dict(grad_clip=dict(max_norm=10, norm_type=2)) lr_config = dict(policy='step', warmup=None, step=[24, 32]) # runtime settings runner = dict(type='EpochBasedRunner', max_epochs=36) ================================================ FILE: open_loop_training/configs/_base_/schedules/seg_cosine_150e.py ================================================ # optimizer # This schedule is mainly used on S3DIS dataset in segmentation task optimizer = dict(type='SGD', lr=0.2, weight_decay=0.0001, momentum=0.9) optimizer_config = dict(grad_clip=None) lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=0.002) momentum_config = None # runtime settings runner = dict(type='EpochBasedRunner', max_epochs=150) ================================================ FILE: open_loop_training/configs/_base_/schedules/seg_cosine_200e.py ================================================ # optimizer # This schedule is mainly used on ScanNet dataset in segmentation task optimizer = dict(type='Adam', lr=0.001, weight_decay=0.01) optimizer_config = dict(grad_clip=None) lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5) momentum_config = None # runtime settings runner = dict(type='EpochBasedRunner', max_epochs=200) ================================================ FILE: open_loop_training/configs/_base_/schedules/seg_cosine_50e.py ================================================ # optimizer # This schedule is mainly used on S3DIS dataset in segmentation task optimizer = dict(type='Adam', lr=0.001, weight_decay=0.001) optimizer_config = dict(grad_clip=None) lr_config = dict(policy='CosineAnnealing', warmup=None, min_lr=1e-5) momentum_config = None # runtime settings runner = dict(type='EpochBasedRunner', max_epochs=50) ================================================ FILE: open_loop_training/configs/thinktwice.py ================================================ _base_ = [ './_base_/default_runtime.py', ] dev_max_sample_per_town = {"town01":10, "town02":10, "town03":10, "town04":10, "town05":10, "town06":10, "town07":10, "town10":10} local_dev_train = ["town01_00", ] local_dev_val = ["town01_00", ] tcp_max_sample_per_town = {"town01":50384, "town02":55943, "town03":42771, "town04":47954, "town05":53684, "town06":48415, "town07":51549, "town10":59898} ## tcp num train_towns = ["01", "03", "04", "06"] val_twons = ["02", "05"] index_per_down = ["val"] + [str(_).zfill(2) for _ in range(0, 12)] tcp_train = [] for town in train_towns: for town_index in index_per_down: tcp_train.append("town"+town + "_" + town_index) tcp_val = [] for town in val_twons: for town_index in index_per_down: tcp_val.append("town"+town + "_" + town_index) full_towns = ["01", "02", "03", "04", "05", "06", "07", "10"] full_train = [] full_val = [] for town in full_towns: for town_index in index_per_down: if "val" == town_index: full_val.append("town"+town + "_" + town_index) else: full_train.append("town"+town + "_" + town_index) max_sample_per_town_full = {"town01":1e9, "town02":1e9, "town03":1e9, "town04":1e9, "town05":1e9, "town06":1e9, "town07":1e9, "town10":1e9} plugin = True plugin_dir = 'code/' img_aug = True SyncBN=True point_cloud_range = [-8.0, -19.2, -4.0, 30.4, 19.2, 10.0] ## The same as Roach cfg = dict( ###From TCP pred_len = 4, # future waypoints predicted turn_KP = 0.75, turn_KI = 0.75, turn_KD = 0.3, turn_n = 40, # buffer size speed_KP = 5.0, speed_KI = 0.5, speed_KD = 1.0, speed_n = 40, # buffer size brake_speed = 0.4, # desired speed below which brake is triggered brake_ratio = 1.1, # ratio of speed to desired speed at which brake is triggered clip_delta = 0.25, # maximum change in speed input to logitudinal controller aim_dist = 4.0, # distance to search around for aim point angle_thresh = 0.3, # outlier control detection angle dist_thresh = 10, # target point y-distance for outlier filtering speed_weight = 0.05, value_weight = 0.001, features_weight = 0.05, img_aug=img_aug, ## ThinkTwice configuration undistort = True, ## Use the intrinsics of undistorted images unreal_coord = True, ## Use the coordinate system of Carla - Unreal https://carla.readthedocs.io/en/0.9.10/core_actors/ is_dev=False, ## Turn it into True when running on a small dataset for debug is_local=True, ## Ignore it since we train our model on a cluster with ceph is_full=False, ## Set it as True will use the size of dataset exactly the same as TCP, while set it as False will use all possible data recorded in the ../dataset/dataset_metadata.pkl refine_num=5, total_epochs = 60, ## For 16 A100; With less GPUs, you could train less epochs ceph_conf="~/petreloss.conf", FPN_out_channels=[256, 256, 256, 256], point_cloud_range=point_cloud_range, SyncBN=SyncBN, ) ckpt_interval = 1 batch_size_per_gpu = 8 ## 2 for 3090, 3 for V100, 8 for A100 if cfg["is_dev"]: cfg["train_town"] = local_dev_train cfg["val_town"] = local_dev_val cfg["max_sample_per_town"] = dev_max_sample_per_town num_worker_per_gpu = 0 else: if cfg["is_full"]: cfg["train_town"] = full_train cfg["val_town"] = full_val cfg["max_sample_per_town"] = max_sample_per_town_full else: cfg["train_town"] = tcp_train cfg["val_town"] = tcp_val cfg["max_sample_per_town"] = tcp_max_sample_per_town num_worker_per_gpu = 8 bev_h = 21 ## The number of BEV grid bev_w = 21 ## The number of BEV grid cfg["history_query_index_lis"] = [-1, 0] ## The index of frames used for BEV encoder cfg["queue_length"] = len(cfg["history_query_index_lis"]) ## The index of frames used for BEV encoder camera_list = ['rgb_front', 'rgb_left', 'rgb_right', 'rgb_back'] num_cams = len(camera_list) cfg['camera_names'] = camera_list cfg["num_cams"] = num_cams cfg['use_depth'] = True ## During Training cfg['use_seg'] = True ## During Training cfg['seg_label_idxs'] = [1,4,5,6,7,8,10,12,18] cfg["num_seg_type"] = len(cfg['seg_label_idxs'])+2 ##From BEVDepth: https://github.com/Megvii-BaseDetection/BEVDepth, data augmentation ida_aug_conf = { 'resize_lim': (0.56, 0.6255), 'final_dim':(448, 896), 'rot_lim': (0, 0), 'H': 900, 'W': 1600, 'rand_flip': True, 'bot_pct_lim': (0.0, 0.0), } cfg["img_size"] = ida_aug_conf['final_dim'] model = dict( type='EncoderDecoder', decoder=dict( type='ThinkTwiceDecoder', config=cfg, bev_h = bev_h, bev_w = bev_w, ), img_encoder=dict( type='LSS', ## Same BEV range with Roach x_bound=[-8.0, 30.4, 1.8285], y_bound=[-19.2, 19.2, 1.8285], z_bound=[-4, 10, 14], d_bound=[1.0, 41.0, 0.5], final_dim=cfg["img_size"], output_channels=256, downsample_factor=16, queue_len=cfg['queue_length'], img_backbone_conf = dict( type='ResNet', depth=50, frozen_stages=-1, out_indices=[0, 1, 2, 3], norm_eval=False, init_cfg=dict(type='Pretrained', checkpoint='torchvision://resnet50'), ), img_neck_conf = dict( type='PAFPN', in_channels=[256, 512, 1024, 2048], num_outs=4, out_channels=256, ), depth_net_conf=dict(in_channels=512, mid_channels=512), seg_net_conf=dict(in_channels=512, out_channels=cfg["num_seg_type"]+1), fpn_in_channels=[256, 256, 256, 256], ), lidar_encoder=dict( type='LidarNet', pts_voxel_layer=dict( max_num_points=10, voxel_size=[0.0571428, 0.0571428, 0.2], max_voxels=(120000, 160000), point_cloud_range = point_cloud_range), pts_voxel_encoder=dict(type='HardSimpleVFE', num_features=5), pts_middle_encoder=dict( type='SparseEncoder_fp32', in_channels=5, sparse_shape=[41, 672, 672], output_channels=128, order=('conv', 'norm', 'act'), encoder_channels=((16, 16, 32), (32, 32, 64), (64, 64, 128), (128, 128)), encoder_paddings=((0, 0, 1), (0, 0, 1), (0, 0, [0, 1, 1]), (0, 0)), block_type='basicblock'), pts_backbone=dict( type='SECOND', in_channels=256, out_channels=[128, 256], layer_nums=[5, 5], layer_strides=[1, 2], norm_cfg=dict(type='BN', eps=0.001, momentum=0.01), conv_cfg=dict(type='Conv2d', bias=False)), pts_neck=dict( type='SECONDFPN', in_channels=[128, 256], out_channels=[256, 256], upsample_strides=[1, 2], norm_cfg=dict(type='BN', eps=0.001, momentum=0.01), upsample_cfg=dict(type='deconv', bias=False), use_conv_for_no_stride=True), ), use_depth=cfg['use_depth'], num_cams=num_cams, train_cfg=cfg, test_cfg=cfg, ) dataset_type = 'CarlaDataset' file_client_args = dict(backend='disk') #fp16 = dict(loss_scale="dynamic") ## Use amp if you are familiar with debugging overflow gradients train_pipeline = [ dict(type='LoadPoints', is_local=cfg["is_local"], coord_type='LIDAR', load_dim=4, use_dim=4, ceph_conf=cfg["ceph_conf"]), dict(type='LoadMultiImages', is_local=cfg["is_local"], camera_names=camera_list, ceph_conf=cfg["ceph_conf"]), dict(type='LoadDepth', is_local=cfg["is_local"], camera_names=camera_list, ceph_conf=cfg["ceph_conf"]), dict(type='LoadSeg', is_local=cfg["is_local"], camera_names=camera_list, seg_label_idxs=cfg['seg_label_idxs'], ceph_conf=cfg["ceph_conf"]), dict(type='CarlaFormatBundle'), dict(type='CarlaCollect', keys=[ 'img', 'points', 'depth', 'seg', 'waypoints', 'target_point', 'target_command', 'target_command_raw', 'speed', "future_speed", 'value', "future_value", 'feature', 'future_feature', "grid_feature", "future_grid_feature", 'action_sigma', 'action_mu', 'future_action_mu', 'future_action_sigma'],) ] test_pipeline = [ dict(type='LoadPoints', is_local=cfg["is_local"], coord_type='LIDAR', load_dim=4, use_dim=4, ceph_conf=cfg["ceph_conf"]), dict(type='LoadMultiImages', is_local=cfg["is_local"], camera_names=camera_list, ceph_conf=cfg["ceph_conf"]), dict(type='LoadDepth', is_local=cfg["is_local"], camera_names=camera_list, ceph_conf=cfg["ceph_conf"]), dict(type='LoadSeg', is_local=cfg["is_local"], camera_names=camera_list, seg_label_idxs=cfg['seg_label_idxs'], ceph_conf=cfg["ceph_conf"]), dict(type='CarlaFormatBundle'), dict(type='CarlaCollect', keys=[ 'img', 'points', 'depth', 'seg', 'waypoints', 'target_point', 'target_command', 'target_command_raw', 'speed', "future_speed", 'value', "future_value", 'feature', 'future_feature', "grid_feature", "future_grid_feature", 'action_sigma', 'action_mu', 'future_action_mu', 'future_action_sigma']) ] train_full_queue_pipeline = [ dict(type='IDAImageTransform', cfg=cfg, ida_aug_conf=ida_aug_conf, is_train=True), dict(type='ImageTransformMulti', aug=True, batch_size=batch_size_per_gpu), ] val_full_queue_pipeline = [ dict(type='IDAImageTransform', cfg=cfg, ida_aug_conf=ida_aug_conf, is_train=False), dict(type='ImageTransformMulti', aug=False, batch_size=batch_size_per_gpu), ] data = dict( samples_per_gpu=batch_size_per_gpu, workers_per_gpu=num_worker_per_gpu, train=dict( type=dataset_type, cfg=cfg, used_town=cfg["train_town"], pipeline=train_pipeline, full_queue_pipeline=train_full_queue_pipeline, is_local=cfg["is_local"], test_mode=False ), val=dict( type=dataset_type, cfg = cfg, used_town=cfg["val_town"], pipeline=test_pipeline, full_queue_pipeline=val_full_queue_pipeline, is_local=cfg["is_local"], test_mode = False ), test=dict( type=dataset_type, cfg = cfg, used_town=cfg["val_town"], pipeline=test_pipeline, full_queue_pipeline=val_full_queue_pipeline, is_local=cfg["is_local"], test_mode = False ), shuffler_sampler=dict(type='DistributedGroupSampler'), nonshuffler_sampler=dict(type='DistributedSampler') ) optimizer = dict( type='AdamW', lr=1e-4, ## 1e-4 - 16 A100; For less GPUs, please use smaller lr such as 3e-5 for stable training weight_decay=1e-7,) optimizer_config = dict(grad_clip=dict(max_norm=100, norm_type=2)) # learning policy lr_config = dict( policy='CosineAnnealing', warmup='linear', warmup_iters=1000, warmup_ratio=1.0 / 3, min_lr_ratio=1e-3) total_epochs = cfg["total_epochs"] evaluation = dict(interval=1) runner = dict(type='EpochBasedRunner', max_epochs=total_epochs) if cfg["is_dev"]: log_interval = 1 else: log_interval = 100 log_config = dict( interval=log_interval, hooks=[ dict(type='TextLoggerHook'), dict(type='TensorboardLoggerHook') ]) checkpoint_config = dict(interval=ckpt_interval) ================================================ FILE: open_loop_training/ops/voxel_pooling/__init__.py ================================================ from .voxel_pooling import voxel_pooling __all__ = ['voxel_pooling'] ================================================ FILE: open_loop_training/ops/voxel_pooling/src/voxel_pooling_forward.cpp ================================================ // Copyright (c) Megvii Inc. All rights reserved. #include #include #include #include #include #include #define CHECK_CUDA(x) \ TORCH_CHECK(x.type().is_cuda(), #x, " must be a CUDAtensor ") #define CHECK_CONTIGUOUS(x) \ TORCH_CHECK(x.is_contiguous(), #x, " must be contiguous ") #define CHECK_INPUT(x) \ CHECK_CUDA(x); \ CHECK_CONTIGUOUS(x) int voxel_pooling_forward_wrapper(int batch_size, int num_points, int num_channels, int num_voxel_x, int num_voxel_y, int num_voxel_z, at::Tensor geom_xyz_tensor, at::Tensor input_features_tensor, at::Tensor output_features_tensor, at::Tensor pos_memo_tensor); void voxel_pooling_forward_kernel_launcher(int batch_size, int num_points, int num_channels, int num_voxel_x, int num_voxel_y, int num_voxel_z, const int *geom_xyz, const float *input_features, float *output_features, int *pos_memo, cudaStream_t stream); int voxel_pooling_forward_wrapper(int batch_size, int num_points, int num_channels, int num_voxel_x, int num_voxel_y, int num_voxel_z, at::Tensor geom_xyz_tensor, at::Tensor input_features_tensor, at::Tensor output_features_tensor, at::Tensor pos_memo_tensor) { CHECK_INPUT(geom_xyz_tensor); CHECK_INPUT(input_features_tensor); const int *geom_xyz = geom_xyz_tensor.data_ptr(); const float *input_features = input_features_tensor.data_ptr(); float *output_features = output_features_tensor.data_ptr(); int *pos_memo = pos_memo_tensor.data_ptr(); cudaStream_t stream = at::cuda::getCurrentCUDAStream().stream(); voxel_pooling_forward_kernel_launcher(batch_size, num_points, num_channels, num_voxel_x, num_voxel_y, num_voxel_z, geom_xyz, input_features, output_features, pos_memo, stream); return 1; } PYBIND11_MODULE(TORCH_EXTENSION_NAME, m) { m.def("voxel_pooling_forward_wrapper", &voxel_pooling_forward_wrapper, "voxel_pooling_forward_wrapper"); } ================================================ FILE: open_loop_training/ops/voxel_pooling/src/voxel_pooling_forward_cuda.cu ================================================ // Copyright (c) Megvii Inc. All rights reserved. #include #include #include #define THREADS_PER_BLOCK 256 #define DIVUP(m, n) ((m) / (n) + ((m) % (n) > 0)) __global__ void voxel_pooling_forward_kernel(int batch_size, int num_points, int num_channels, int num_voxel_x, int num_voxel_y, int num_voxel_z, const int *geom_xyz, const float *input_features, float *output_features, int *pos_memo) { // Each thread process only one channel of one voxel. int blk_idx = blockIdx.x; int thd_idx = threadIdx.x; int pt_idx = blk_idx * blockDim.x + thd_idx; if (pt_idx >= batch_size * num_points) { return; } else { int batch_idx = pt_idx / num_points; int x = geom_xyz[pt_idx * 3]; int y = geom_xyz[pt_idx * 3 + 1]; int z = geom_xyz[pt_idx * 3 + 2]; // if coord of current voxel is out of boundary, return. if (x < 0 || x >= num_voxel_x || y < 0 || y >= num_voxel_y || z < 0 || z >= num_voxel_z) { return; } pos_memo[pt_idx * 3] = batch_idx; pos_memo[pt_idx * 3 + 1] = y; pos_memo[pt_idx * 3 + 2] = x; for (int channel_idx = 0; channel_idx < num_channels; channel_idx++) { atomicAdd( &output_features[(batch_idx * num_voxel_y * num_voxel_x + y * num_voxel_x + x) * num_channels + channel_idx], input_features[pt_idx * num_channels + channel_idx]); } } } void voxel_pooling_forward_kernel_launcher(int batch_size, int num_points, int num_channels, int num_voxel_x, int num_voxel_y, int num_voxel_z, const int *geom_xyz, const float *input_features, float *output_features, int *pos_memo, cudaStream_t stream) { cudaError_t err; dim3 blocks(DIVUP(batch_size * num_points, THREADS_PER_BLOCK)); // blockIdx.x(col), blockIdx.y(row) dim3 threads(THREADS_PER_BLOCK); voxel_pooling_forward_kernel<<>>(batch_size, num_points, num_channels, num_voxel_x, num_voxel_y, num_voxel_z, geom_xyz, input_features, output_features, pos_memo); // cudaDeviceSynchronize(); // for using printf in kernel function err = cudaGetLastError(); if (cudaSuccess != err) { fprintf(stderr, "CUDA kernel failed : %s\n", cudaGetErrorString(err)); exit(-1); } } ================================================ FILE: open_loop_training/ops/voxel_pooling/voxel_pooling.py ================================================ # Copyright (c) Megvii Inc. All rights reserved. import torch from torch.autograd import Function from . import voxel_pooling_ext class VoxelPooling(Function): @staticmethod def forward(ctx, geom_xyz: torch.Tensor, input_features: torch.Tensor, voxel_num: torch.Tensor) -> torch.Tensor: """Forward function for `voxel pooling. Args: geom_xyz (Tensor): xyz coord for each voxel with the shape of [B, N, 3]. input_features (Tensor): feature for each voxel with the shape of [B, N, C]. voxel_num (Tensor): Number of voxels for each dim with the shape of [3]. Returns: Tensor: (B, C, H, W) bev feature map. """ assert geom_xyz.is_contiguous() assert input_features.is_contiguous() # no gradient for input_features and geom_feats ctx.mark_non_differentiable(geom_xyz) grad_input_features = torch.zeros_like(input_features) geom_xyz = geom_xyz.reshape(geom_xyz.shape[0], -1, geom_xyz.shape[-1]) input_features = input_features.reshape( (geom_xyz.shape[0], -1, input_features.shape[-1])) assert geom_xyz.shape[1] == input_features.shape[1] batch_size = input_features.shape[0] num_points = input_features.shape[1] num_channels = input_features.shape[2] output_features = input_features.new_zeros(batch_size, voxel_num[1], voxel_num[0], num_channels) # Save the position of bev_feature_map for each input point. pos_memo = geom_xyz.new_ones(batch_size, num_points, 3) * -1 voxel_pooling_ext.voxel_pooling_forward_wrapper( batch_size, num_points, num_channels, voxel_num[0], voxel_num[1], voxel_num[2], geom_xyz, input_features, output_features, pos_memo, ) # save grad_input_features and pos_memo for backward ctx.save_for_backward(grad_input_features, pos_memo) return output_features.permute(0, 3, 1, 2) @staticmethod def backward(ctx, grad_output_features): (grad_input_features, pos_memo) = ctx.saved_tensors kept = (pos_memo != -1)[..., 0] grad_input_features_shape = grad_input_features.shape grad_input_features = grad_input_features.reshape( grad_input_features.shape[0], -1, grad_input_features.shape[-1]) grad_input_features[kept] = grad_output_features[ pos_memo[kept][..., 0].long(), :, pos_memo[kept][..., 1].long(), pos_memo[kept][..., 2].long()] grad_input_features = grad_input_features.reshape( grad_input_features_shape) return None, grad_input_features, None voxel_pooling = VoxelPooling.apply ================================================ FILE: open_loop_training/setup.py ================================================ # setup.py from setuptools import setup import os import torch from torch.utils.cpp_extension import BuildExtension, CUDAExtension def make_cuda_ext(name, module, sources, sources_cuda=[], extra_args=[], extra_include_path=[]): define_macros = [] extra_compile_args = {'cxx': [] + extra_args} if torch.cuda.is_available() or os.getenv('FORCE_CUDA', '0') == '1': define_macros += [('WITH_CUDA', None)] extension = CUDAExtension extra_compile_args['nvcc'] = extra_args + [ '-D__CUDA_NO_HALF_OPERATORS__', '-D__CUDA_NO_HALF_CONVERSIONS__', '-D__CUDA_NO_HALF2_OPERATORS__', ] sources += sources_cuda else: raise EnvironmentError('CUDA is required to compile MMDetection!') return extension( name='{}.{}'.format(module, name), sources=[os.path.join(*module.split('.'), p) for p in sources], include_dirs=extra_include_path, define_macros=define_macros, extra_compile_args=extra_compile_args, ) setup( name='voxel_pooling', ext_modules=[ make_cuda_ext( name='voxel_pooling_ext', module='ops.voxel_pooling', sources=['src/voxel_pooling_forward.cpp'], sources_cuda=['src/voxel_pooling_forward_cuda.cu'], ), ], cmdclass={'build_ext': BuildExtension}) ================================================ FILE: open_loop_training/train.py ================================================ # --------------------------------------------- # Copyright (c) OpenMMLab. All rights reserved. # --------------------------------------------- # Modified by Zhiqi Li # Modified by Xiaosong Jia # --------------------------------------------- from __future__ import division import argparse import copy import mmcv import os import time import torch import warnings from mmcv import Config, DictAction from mmcv.runner import get_dist_info, init_dist from os import path as osp from mmdet import __version__ as mmdet_version from mmdet3d import __version__ as mmdet3d_version #from mmdet3d.apis import train_model from mmdet3d.datasets import build_dataset from mmdet3d.models import build_model from mmdet3d.utils import collect_env, get_root_logger from mmdet.apis import set_random_seed from mmseg import __version__ as mmseg_version from mmcv.utils import TORCH_VERSION, digit_version torch.hub.set_dir("./ckpt") def str2bool(v): if isinstance(v, bool): return v if v.lower() in ('yes', 'true', 't', 'y', '1'): return True elif v.lower() in ('no', 'false', 'f', 'n', '0'): return False else: raise argparse.ArgumentTypeError('Boolean value expected.') def parse_args(): parser = argparse.ArgumentParser(description='Train a detector') parser.add_argument('config', help='train config file path') parser.add_argument('--work-dir', help='the dir to save logs and models') parser.add_argument( '--resume-from', help='the checkpoint file to resume from') parser.add_argument( '--load-from', help='the checkpoint file to resume from') parser.add_argument( '--no-validate', action='store_true', help='whether not to evaluate the checkpoint during training') group_gpus = parser.add_mutually_exclusive_group() group_gpus.add_argument( '--gpus', type=int, help='number of gpus to use ' '(only applicable to non-distributed training)') group_gpus.add_argument( '--gpu-ids', type=int, nargs='+', help='ids of gpus to use ' '(only applicable to non-distributed training)') parser.add_argument('--seed', type=int, default=0, help='random seed') parser.add_argument( '--deterministic', action='store_true', help='whether to set deterministic options for CUDNN backend.') parser.add_argument( '--options', nargs='+', action=DictAction, help='override some settings in the used config, the key-value pair ' 'in xxx=yyy format will be merged into config file (deprecate), ' 'change to --cfg-options instead.') parser.add_argument( '--cfg-options', nargs='+', action=DictAction, help='override some settings in the used config, the key-value pair ' 'in xxx=yyy format will be merged into config file. If the value to ' 'be overwritten is a list, it should be like key="[a,b]" or key=a,b ' 'It also allows nested list/tuple values, e.g. key="[(a,b),(c,d)]" ' 'Note that the quotation marks are necessary and that no white space ' 'is allowed.') parser.add_argument( '--launcher', choices=['none', 'pytorch', 'slurm', 'mpi'], default='none', help='job launcher') parser.add_argument('--local_rank', type=int, default=0) parser.add_argument( '--autoscale-lr', action='store_true', help='automatically scale lr with the number of gpus') args = parser.parse_args() if 'LOCAL_RANK' not in os.environ: os.environ['LOCAL_RANK'] = str(args.local_rank) if args.options and args.cfg_options: raise ValueError( '--options and --cfg-options cannot be both specified, ' '--options is deprecated in favor of --cfg-options') if args.options: warnings.warn('--options is deprecated in favor of --cfg-options') args.cfg_options = args.options return args def main(): args = parse_args() cfg = Config.fromfile(args.config) if args.cfg_options is not None: cfg.merge_from_dict(args.cfg_options) # import modules from string list. if cfg.get('custom_imports', None): from mmcv.utils import import_modules_from_strings import_modules_from_strings(**cfg['custom_imports']) # import modules from plguin/xx, registry will be updated if hasattr(cfg, 'plugin'): if cfg.plugin: import importlib if hasattr(cfg, 'plugin_dir'): plugin_dir = cfg.plugin_dir _module_dir = os.path.dirname(plugin_dir) _module_dir = _module_dir.split('/') _module_path = _module_dir[0] for m in _module_dir[1:]: _module_path = _module_path + '.' + m print(_module_path) plg_lib = importlib.import_module(_module_path) else: # import dir is the dirpath for the config file _module_dir = os.path.dirname(args.config) _module_dir = _module_dir.split('/') _module_path = _module_dir[0] for m in _module_dir[1:]: _module_path = _module_path + '.' + m print(_module_path) plg_lib = importlib.import_module(_module_path) from code.apis.train import custom_train_model # set cudnn_benchmark if cfg.get('cudnn_benchmark', False): torch.backends.cudnn.benchmark = True # work_dir is determined in this priority: CLI > segment in file > filename if args.work_dir is not None: # update configs according to CLI args if args.work_dir is not None cfg.work_dir = args.work_dir elif cfg.get('work_dir', None) is None: # use config filename as default work_dir if cfg.work_dir is None cfg.work_dir = osp.join('./work_dirs', osp.splitext(osp.basename(args.config))[0]) # if args.resume_from is not None: if args.resume_from is not None and osp.isfile(args.resume_from): cfg.resume_from = args.resume_from if args.load_from is not None and osp.isfile(args.load_from): cfg.load_from = args.load_from if args.gpu_ids is not None: cfg.gpu_ids = args.gpu_ids else: cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus) # init distributed env first, since logger depends on the dist info. if args.launcher == 'none': distributed = False else: distributed = True init_dist(args.launcher, **cfg.dist_params) # re-set gpu_ids with distributed training mode _, world_size = get_dist_info() cfg.gpu_ids = range(world_size) # create work_dir mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir)) # dump config cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config))) # init the logger before other steps timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime()) log_file = osp.join(cfg.work_dir, f'{timestamp}.log') # specify logger name, if we still use 'mmdet', the output info will be # filtered and won't be saved in the log_file if cfg.model.type in ['EncoderDecoder3D']: logger_name = 'mmseg' else: logger_name = 'mmdet' logger = get_root_logger( log_file=log_file, log_level=cfg.log_level, name=logger_name) # init the meta dict to record some important information such as # environment info and seed, which will be logged meta = dict() # log env info env_info_dict = collect_env() env_info = '\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()]) dash_line = '-' * 60 + '\n' logger.info('Environment info:\n' + dash_line + env_info + '\n' + dash_line) meta['env_info'] = env_info meta['config'] = cfg.pretty_text # log some basic info logger.info(f'Distributed training: {distributed}') logger.info(f'Config:\n{cfg.pretty_text}') # set random seeds if args.seed is not None: logger.info(f'Set random seed to {args.seed}, ' f'deterministic: {args.deterministic}') set_random_seed(args.seed, deterministic=args.deterministic) cfg.seed = args.seed meta['seed'] = args.seed meta['exp_name'] = osp.basename(args.config) model = build_model( cfg.model, train_cfg=cfg.get('train_cfg'), test_cfg=cfg.get('test_cfg')) model.init_weights() logger.info(f'Model:\n{model}') datasets = [build_dataset(cfg.data.train)] if len(cfg.workflow) == 2: val_dataset = copy.deepcopy(cfg.data.val) # in case we use a dataset wrapper if 'dataset' in cfg.data.train: val_dataset.pipeline = cfg.data.train.dataset.pipeline else: val_dataset.pipeline = cfg.data.train.pipeline val_dataset.test_mode = False datasets.append(build_dataset(val_dataset)) custom_train_model( model, datasets, cfg, distributed=distributed, validate=(not args.no_validate), timestamp=timestamp, meta=meta) if __name__ == '__main__': main() ================================================ FILE: roach/config/config_agent.yaml ================================================ entry_point: roach.rl_birdview_agent:RlBirdviewAgent wb_run_path: null wb_ckpt_step: null env_wrapper: entry_point: roach.utils.rl_birdview_wrapper:RlBirdviewWrapper kwargs: input_states: - control - vel_xy acc_as_action: true policy: entry_point: roach.models.ppo_policy:PpoPolicy kwargs: policy_head_arch: - 256 - 256 value_head_arch: - 256 - 256 features_extractor_entry_point: roach.models.torch_layers:XtMaCNN features_extractor_kwargs: states_neurons: - 256 - 256 distribution_entry_point: roach.models.distributions:BetaDistribution distribution_kwargs: dist_init: null training: entry_point: roach.models.ppo:PPO kwargs: learning_rate: 1.0e-05 n_steps_total: 12288 batch_size: 256 n_epochs: 20 gamma: 0.99 gae_lambda: 0.9 clip_range: 0.2 clip_range_vf: null ent_coef: 0.01 explore_coef: 0.05 vf_coef: 0.5 max_grad_norm: 0.5 target_kl: 0.01 update_adv: false lr_schedule_step: 8 obs_configs: birdview: module: birdview.chauffeurnet width_in_pixels: 192 pixels_ev_to_bottom: 40 pixels_per_meter: 5.0 history_idx: - -16 - -11 - -6 - -1 scale_bbox: true scale_mask_col: 1.0 speed: module: actor_state.speed control: module: actor_state.control velocity: module: actor_state.velocity ================================================ FILE: roach/criteria/blocked.py ================================================ import numpy as np class Blocked(): def __init__(self, speed_threshold=0.1, below_threshold_max_time=90.0): self._speed_threshold = speed_threshold self._below_threshold_max_time = below_threshold_max_time self._time_last_valid_state = None def tick(self, vehicle, timestamp): info = None linear_speed = self._calculate_speed(vehicle.get_velocity()) if linear_speed < self._speed_threshold and self._time_last_valid_state: if (timestamp['relative_simulation_time'] - self._time_last_valid_state) > self._below_threshold_max_time: # The actor has been "blocked" for too long ev_loc = vehicle.get_location() info = { 'step': timestamp['step'], 'simulation_time': timestamp['relative_simulation_time'], 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z] } else: self._time_last_valid_state = timestamp['relative_simulation_time'] return info @staticmethod def _calculate_speed(carla_velocity): return np.linalg.norm([carla_velocity.x, carla_velocity.y]) ================================================ FILE: roach/criteria/collision.py ================================================ import carla import weakref import numpy as np class Collision(): def __init__(self, vehicle, carla_world, intensity_threshold=0.0, min_area_of_collision=3, max_area_of_collision=5, max_id_time=5): blueprint = carla_world.get_blueprint_library().find('sensor.other.collision') self._collision_sensor = carla_world.spawn_actor(blueprint, carla.Transform(), attach_to=vehicle) self._collision_sensor.listen(lambda event: self._on_collision(weakref.ref(self), event)) self._collision_info = None self.registered_collisions = [] self.last_id = None self.collision_time = None # If closer than this distance, the collision is ignored self._min_area_of_collision = min_area_of_collision # If further than this distance, the area is forgotten self._max_area_of_collision = max_area_of_collision # Amount of time the last collision if is remembered self._max_id_time = max_id_time # intensity_threshold, LBC uses 400, leaderboard does not use it (set to 0) self._intensity_threshold = intensity_threshold def tick(self, vehicle, timestamp): ev_loc = vehicle.get_location() new_registered_collisions = [] # Loops through all the previous registered collisions for collision_location in self.registered_collisions: distance = ev_loc.distance(collision_location) # If far away from a previous collision, forget it if distance <= self._max_area_of_collision: new_registered_collisions.append(collision_location) self.registered_collisions = new_registered_collisions if self.last_id and timestamp['relative_simulation_time'] - self.collision_time > self._max_id_time: self.last_id = None info = self._collision_info self._collision_info = None if info is not None: info['step'] -= timestamp['start_frame'] info['simulation_time'] -= timestamp['start_simulation_time'] return info @staticmethod def _on_collision(weakself, event): self = weakself() if not self: return # Ignore the current one if it's' the same id as before if self.last_id == event.other_actor.id: return # Ignore if it's too close to a previous collision (avoid micro collisions) ev_loc = event.actor.get_transform().location for collision_location in self.registered_collisions: if ev_loc.distance(collision_location) <= self._min_area_of_collision: return # Ignore if its intensity is smaller than self._intensity_threshold impulse = event.normal_impulse intensity = np.linalg.norm([impulse.x, impulse.y, impulse.z]) if intensity < self._intensity_threshold: return # collision_type if ('static' in event.other_actor.type_id or 'traffic' in event.other_actor.type_id) \ and 'sidewalk' not in event.other_actor.type_id: collision_type = 0 # TrafficEventType.COLLISION_STATIC elif 'vehicle' in event.other_actor.type_id: collision_type = 1 # TrafficEventType.COLLISION_VEHICLE elif 'walker' in event.other_actor.type_id: collision_type = 2 # TrafficEventType.COLLISION_PEDESTRIAN else: collision_type = -1 # write to info, all quantities in in world coordinate event_loc = event.transform.location event_rot = event.transform.rotation oa_loc = event.other_actor.get_transform().location oa_rot = event.other_actor.get_transform().rotation oa_vel = event.other_actor.get_velocity() ev_rot = event.actor.get_transform().rotation ev_vel = event.actor.get_velocity() self._collision_info = { 'step': event.frame, 'simulation_time': event.timestamp, 'collision_type': collision_type, 'other_actor_id': event.other_actor.id, 'other_actor_type_id': event.other_actor.type_id, 'intensity': intensity, 'normal_impulse': [impulse.x, impulse.y, impulse.z], 'event_loc': [event_loc.x, event_loc.y, event_loc.z], 'event_rot': [event_rot.roll, event_rot.pitch, event_rot.yaw], 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z], 'ev_rot': [ev_rot.roll, ev_rot.pitch, ev_rot.yaw], 'ev_vel': [ev_vel.x, ev_vel.y, ev_vel.z], 'oa_loc': [oa_loc.x, oa_loc.y, oa_loc.z], 'oa_rot': [oa_rot.roll, oa_rot.pitch, oa_rot.yaw], 'oa_vel': [oa_vel.x, oa_vel.y, oa_vel.z] } self.collision_time = event.timestamp self.registered_collisions.append(ev_loc) # Number 0: static objects -> ignore it if event.other_actor.id != 0: self.last_id = event.other_actor.id def clean(self): self._collision_sensor.stop() self._collision_sensor.destroy() self._collision_sensor = None ================================================ FILE: roach/criteria/encounter_light.py ================================================ from carla_gym.utils.traffic_light import TrafficLightHandler class EncounterLight(): def __init__(self, dist_threshold=7.5): self._last_light_id = None self._dist_threshold = dist_threshold def tick(self, vehicle, timestamp): info = None light_state, light_loc, light_id = TrafficLightHandler.get_light_state( vehicle, dist_threshold=self._dist_threshold) if light_id is not None: if light_id != self._last_light_id: self._last_light_id = light_id info = { 'step': timestamp['step'], 'simulation_time': timestamp['relative_simulation_time'], 'id': light_id, 'tl_loc': light_loc.tolist() } return info ================================================ FILE: roach/criteria/outside_route_lane.py ================================================ import carla from carla_gym.utils.transforms import cast_angle class OutsideRouteLane(): def __init__(self, carla_map, vehicle_loc, allowed_out_distance=1.3, max_allowed_vehicle_angle=120.0, max_allowed_waypint_angle=150.0): self._map = carla_map self._pre_ego_waypoint = self._map.get_waypoint(vehicle_loc) self._allowed_out_distance = allowed_out_distance self._max_allowed_vehicle_angle = max_allowed_vehicle_angle self._max_allowed_waypint_angle = max_allowed_waypint_angle self._outside_lane_active = False self._wrong_lane_active = False self._last_road_id = None self._last_lane_id = None def tick(self, vehicle, timestamp, distance_traveled): ev_loc = vehicle.get_location() ev_yaw = vehicle.get_transform().rotation.yaw self._is_outside_driving_lanes(ev_loc) self._is_at_wrong_lane(ev_loc, ev_yaw) info = None if self._outside_lane_active or self._wrong_lane_active: info = { 'step': timestamp['step'], 'simulation_time': timestamp['relative_simulation_time'], 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z], 'distance_traveled': distance_traveled, 'outside_lane': self._outside_lane_active, 'wrong_lane': self._wrong_lane_active } return info def _is_outside_driving_lanes(self, location): """ Detects if the ego_vehicle is outside driving/parking lanes """ current_driving_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving, project_to_road=True) current_parking_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Parking, project_to_road=True) driving_distance = location.distance(current_driving_wp.transform.location) if current_parking_wp is not None: # Some towns have no parking parking_distance = location.distance(current_parking_wp.transform.location) else: parking_distance = float('inf') if driving_distance >= parking_distance: distance = parking_distance lane_width = current_parking_wp.lane_width else: distance = driving_distance lane_width = current_driving_wp.lane_width self._outside_lane_active = distance > (lane_width / 2 + self._allowed_out_distance) def _is_at_wrong_lane(self, location, yaw): """ Detects if the ego_vehicle has invaded a wrong driving lane """ current_waypoint = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving, project_to_road=True) current_lane_id = current_waypoint.lane_id current_road_id = current_waypoint.road_id # Lanes and roads are too chaotic at junctions if current_waypoint.is_junction: self._wrong_lane_active = False elif self._last_road_id != current_road_id or self._last_lane_id != current_lane_id: # Route direction can be considered continuous, except after exiting a junction. if self._pre_ego_waypoint.is_junction: # cast angle to [-180, +180) vehicle_lane_angle = cast_angle( current_waypoint.transform.rotation.yaw - yaw) self._wrong_lane_active = abs(vehicle_lane_angle) > self._max_allowed_vehicle_angle else: # Check for a big gap in waypoint directions. waypoint_angle = cast_angle( current_waypoint.transform.rotation.yaw - self._pre_ego_waypoint.transform.rotation.yaw) if abs(waypoint_angle) >= self._max_allowed_waypint_angle: # Is the ego vehicle going back to the lane, or going out? Take the opposite self._wrong_lane_active = not bool(self._wrong_lane_active) else: # Changing to a lane with the same direction self._wrong_lane_active = False # Remember the last state self._last_lane_id = current_lane_id self._last_road_id = current_road_id self._pre_ego_waypoint = current_waypoint ================================================ FILE: roach/criteria/route_deviation.py ================================================ class RouteDeviation(): def __init__(self, offroad_min=15, offroad_max=30, max_route_percentage=0.3): self._offroad_min = offroad_min self._offroad_max = offroad_max self._max_route_percentage = max_route_percentage self._out_route_distance = 0.0 def tick(self, vehicle, timestamp, ref_waypoint, distance_traveled, route_length): ev_loc = vehicle.get_location() distance = ev_loc.distance(ref_waypoint.transform.location) # fail if off_route is True off_route_max = distance > self._offroad_max # fail if off_safe_route more than 30% of total route length off_route_min = False if distance > self._offroad_min: self._out_route_distance += distance_traveled out_route_percentage = self._out_route_distance / route_length if out_route_percentage > self._max_route_percentage: off_route_min = True info = None if off_route_max or off_route_min: info = { 'step': timestamp['step'], 'simulation_time': timestamp['relative_simulation_time'], 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z], 'off_route_max': off_route_max, 'off_route_min': off_route_min } return info ================================================ FILE: roach/criteria/run_red_light.py ================================================ import carla import shapely.geometry from carla_gym.utils.traffic_light import TrafficLightHandler class RunRedLight(): def __init__(self, carla_map, distance_light=30): self._map = carla_map self._last_red_light_id = None self._distance_light = distance_light def tick(self, vehicle, timestamp): ev_tra = vehicle.get_transform() ev_loc = ev_tra.location ev_dir = ev_tra.get_forward_vector() ev_extent = vehicle.bounding_box.extent.x tail_close_pt = ev_tra.transform(carla.Location(x=-0.8 * ev_extent)) tail_far_pt = ev_tra.transform(carla.Location(x=-ev_extent - 1.0)) tail_wp = self._map.get_waypoint(tail_far_pt) info = None for idx_tl in range(TrafficLightHandler.num_tl): traffic_light = TrafficLightHandler.list_tl_actor[idx_tl] tl_tv_loc = TrafficLightHandler.list_tv_loc[idx_tl] if tl_tv_loc.distance(ev_loc) > self._distance_light: continue if traffic_light.state != carla.TrafficLightState.Red: continue if self._last_red_light_id and self._last_red_light_id == traffic_light.id: continue for idx_wp in range(len(TrafficLightHandler.list_stopline_wps[idx_tl])): wp = TrafficLightHandler.list_stopline_wps[idx_tl][idx_wp] wp_dir = wp.transform.get_forward_vector() dot_ve_wp = ev_dir.x * wp_dir.x + ev_dir.y * wp_dir.y + ev_dir.z * wp_dir.z if tail_wp.road_id == wp.road_id and tail_wp.lane_id == wp.lane_id and dot_ve_wp > 0: # This light is red and is affecting our lane stop_left_loc, stop_right_loc = TrafficLightHandler.list_stopline_vtx[idx_tl][idx_wp] # Is the vehicle traversing the stop line? if self._is_vehicle_crossing_line((tail_close_pt, tail_far_pt), (stop_left_loc, stop_right_loc)): tl_loc = traffic_light.get_location() # loc_in_ev = trans_utils.loc_global_to_ref(tl_loc, ev_tra) self._last_red_light_id = traffic_light.id info = { 'step': timestamp['step'], 'simulation_time': timestamp['relative_simulation_time'], 'id': traffic_light.id, 'tl_loc': [tl_loc.x, tl_loc.y, tl_loc.z], 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z] } return info @staticmethod def _is_vehicle_crossing_line(seg1, seg2): """ check if vehicle crosses a line segment """ line1 = shapely.geometry.LineString([(seg1[0].x, seg1[0].y), (seg1[1].x, seg1[1].y)]) line2 = shapely.geometry.LineString([(seg2[0].x, seg2[0].y), (seg2[1].x, seg2[1].y)]) inter = line1.intersection(line2) return not inter.is_empty ================================================ FILE: roach/criteria/run_stop_sign.py ================================================ import carla import numpy as np class RunStopSign(): def __init__(self, carla_world, proximity_threshold=50.0, speed_threshold=0.1, waypoint_step=1.0): self._map = carla_world.get_map() self._proximity_threshold = proximity_threshold self._speed_threshold = speed_threshold self._waypoint_step = waypoint_step all_actors = carla_world.get_actors() self._list_stop_signs = [] for _actor in all_actors: if 'traffic.stop' in _actor.type_id: self._list_stop_signs.append(_actor) self._target_stop_sign = None self._stop_completed = False self._affected_by_stop = False def tick(self, vehicle, timestamp): info = None ev_loc = vehicle.get_location() ev_f_vec = vehicle.get_transform().get_forward_vector() if self._target_stop_sign is None: self._target_stop_sign = self._scan_for_stop_sign(vehicle.get_transform()) if self._target_stop_sign is not None: stop_loc = self._target_stop_sign.get_location() # info = { # 'event': 'encounter', # 'step': timestamp['step'], # 'simulation_time': timestamp['relative_simulation_time'], # 'id': self._target_stop_sign.id, # 'stop_loc': [stop_loc.x, stop_loc.y, stop_loc.z], # 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z] # } else: # we were in the middle of dealing with a stop sign if not self._stop_completed: # did the ego-vehicle stop? current_speed = self._calculate_speed(vehicle.get_velocity()) if current_speed < self._speed_threshold: self._stop_completed = True if not self._affected_by_stop: stop_t = self._target_stop_sign.get_transform() transformed_tv = stop_t.transform(self._target_stop_sign.trigger_volume.location) stop_extent = self._target_stop_sign.trigger_volume.extent if self.point_inside_boundingbox(ev_loc, transformed_tv, stop_extent): self._affected_by_stop = True if not self.is_affected_by_stop(ev_loc, self._target_stop_sign): # is the vehicle out of the influence of this stop sign now? if not self._stop_completed and self._affected_by_stop: # did we stop? stop_loc = self._target_stop_sign.get_transform().location # info = { # 'event': 'run', # 'step': timestamp['step'], # 'simulation_time': timestamp['relative_simulation_time'], # 'id': self._target_stop_sign.id, # 'stop_loc': [stop_loc.x, stop_loc.y, stop_loc.z], # 'ev_loc': [ev_loc.x, ev_loc.y, ev_loc.z] # } # reset state self._target_stop_sign = None self._stop_completed = False self._affected_by_stop = False # return info def _scan_for_stop_sign(self, vehicle_transform): target_stop_sign = None ve_dir = vehicle_transform.get_forward_vector() wp = self._map.get_waypoint(vehicle_transform.location) wp_dir = wp.transform.get_forward_vector() dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z if dot_ve_wp > 0: # Ignore all when going in a wrong lane for stop_sign in self._list_stop_signs: if self.is_affected_by_stop(vehicle_transform.location, stop_sign): # this stop sign is affecting the vehicle target_stop_sign = stop_sign break return target_stop_sign def is_affected_by_stop(self, vehicle_loc, stop, multi_step=20): """ Check if the given actor is affected by the stop """ affected = False # first we run a fast coarse test stop_t = stop.get_transform() stop_location = stop_t.location if stop_location.distance(vehicle_loc) > self._proximity_threshold: return affected transformed_tv = stop_t.transform(stop.trigger_volume.location) # slower and accurate test based on waypoint's horizon and geometric test list_locations = [vehicle_loc] waypoint = self._map.get_waypoint(vehicle_loc) for _ in range(multi_step): if waypoint: next_wps = waypoint.next(self._waypoint_step) if not next_wps: break waypoint = next_wps[0] if not waypoint: break list_locations.append(waypoint.transform.location) for actor_location in list_locations: if self.point_inside_boundingbox(actor_location, transformed_tv, stop.trigger_volume.extent): affected = True return affected @staticmethod def _calculate_speed(carla_velocity): return np.linalg.norm([carla_velocity.x, carla_velocity.y]) @staticmethod def point_inside_boundingbox(point, bb_center, bb_extent): """ X :param point: :param bb_center: :param bb_extent: :return: """ # bugfix slim bbox bb_extent.x = max(bb_extent.x, bb_extent.y) bb_extent.y = max(bb_extent.x, bb_extent.y) # pylint: disable=invalid-name A = carla.Vector2D(bb_center.x - bb_extent.x, bb_center.y - bb_extent.y) B = carla.Vector2D(bb_center.x + bb_extent.x, bb_center.y - bb_extent.y) D = carla.Vector2D(bb_center.x - bb_extent.x, bb_center.y + bb_extent.y) M = carla.Vector2D(point.x, point.y) AB = B - A AD = D - A AM = M - A am_ab = AM.x * AB.x + AM.y * AB.y ab_ab = AB.x * AB.x + AB.y * AB.y am_ad = AM.x * AD.x + AM.y * AD.y ad_ad = AD.x * AD.x + AD.y * AD.y return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad ================================================ FILE: roach/models/distributions.py ================================================ from typing import Optional, Tuple import torch as th import torch.nn as nn from torch.distributions import Beta, Normal from torch.nn import functional as F import numpy as np def sum_independent_dims(tensor: th.Tensor) -> th.Tensor: if len(tensor.shape) > 1: tensor = tensor.sum(dim=1) else: tensor = tensor.sum() return tensor class DiagGaussianDistribution(): def __init__(self, action_dim: int, dist_init=None, action_dependent_std=False): self.distribution = None self.action_dim = action_dim self.dist_init = dist_init self.action_dependent_std = action_dependent_std self.low = None self.high = None self.log_std_max = 2 self.log_std_min = -20 # [mu, log_std], [0, 1] self.acc_exploration_dist = { 'go': th.FloatTensor([0.66, -3]), 'stop': th.FloatTensor([-0.66, -3]) } self.steer_exploration_dist = { 'turn': th.FloatTensor([0.0, -1]), 'straight': th.FloatTensor([3.0, 3.0]) } if th.cuda.is_available(): self.device = 'cuda' else: self.device = 'cpu' def proba_distribution_net(self, latent_dim: int) -> Tuple[nn.Module, nn.Parameter]: mean_actions = nn.Linear(latent_dim, self.action_dim) if self.action_dependent_std: log_std = nn.Linear(latent_dim, self.action_dim) else: log_std = nn.Parameter(-2.0*th.ones(self.action_dim), requires_grad=True) if self.dist_init is not None: # log_std.weight.data.fill_(0.01) # mean_actions.weight.data.fill_(0.01) # acc/steer mean_actions.bias.data[0] = self.dist_init[0][0] mean_actions.bias.data[1] = self.dist_init[1][0] if self.action_dependent_std: log_std.bias.data[0] = self.dist_init[0][1] log_std.bias.data[1] = self.dist_init[1][1] else: init_tensor = th.FloatTensor([self.dist_init[0][1], self.dist_init[1][1]]) log_std = nn.Parameter(init_tensor, requires_grad=True) return mean_actions, log_std def proba_distribution(self, mean_actions: th.Tensor, log_std: th.Tensor) -> "DiagGaussianDistribution": if self.action_dependent_std: log_std = th.clamp(log_std, self.log_std_min, self.log_std_max) action_std = th.ones_like(mean_actions) * log_std.exp() self.distribution = Normal(mean_actions, action_std) return self def log_prob(self, actions: th.Tensor) -> th.Tensor: log_prob = self.distribution.log_prob(actions) return sum_independent_dims(log_prob) def entropy_loss(self) -> th.Tensor: entropy_loss = -1.0 * self.distribution.entropy() return th.mean(entropy_loss) def exploration_loss(self, exploration_suggests) -> th.Tensor: # [('stop'/'go'/None, 'turn'/'straight'/None)] # (batch_size, action_dim) mu = self.distribution.loc.detach().clone() sigma = self.distribution.scale.detach().clone() for i, (acc_suggest, steer_suggest) in enumerate(exploration_suggests): if acc_suggest != '': mu[i, 0] = self.acc_exploration_dist[acc_suggest][0] sigma[i, 0] = self.acc_exploration_dist[acc_suggest][1] if steer_suggest != '': mu[i, 1] = self.steer_exploration_dist[steer_suggest][0] sigma[i, 1] = self.steer_exploration_dist[steer_suggest][1] dist_ent = Normal(mu, sigma) exploration_loss = th.distributions.kl_divergence(dist_ent, self.distribution) return th.mean(exploration_loss) def sample(self) -> th.Tensor: return self.distribution.rsample() def mode(self) -> th.Tensor: return self.distribution.mean def get_actions(self, deterministic: bool = False) -> th.Tensor: if deterministic: return self.mode() return self.sample() class SquashedDiagGaussianDistribution(): def __init__(self, action_dim: int, log_std_init: float = 0.0, action_dependent_std=False): self.distribution = None self.action_dim = action_dim self.log_std_init = log_std_init self.eps = 1e-7 self.action_dependent_std = action_dependent_std self.low = -1.0 self.high = 1.0 self.log_std_max = 2 self.log_std_min = -20 self.gaussian_actions = None def proba_distribution_net(self, latent_dim: int): mean_actions = nn.Linear(latent_dim, self.action_dim) if self.action_dependent_std: log_std = nn.Linear(latent_dim, self.action_dim) else: log_std = nn.Parameter(th.ones(self.action_dim) * self.log_std_init, requires_grad=True) return mean_actions, log_std def proba_distribution(self, mean_actions: th.Tensor, log_std: th.Tensor): if self.action_dependent_std: log_std = th.clamp(log_std, self.log_std_min, self.log_std_max) action_std = th.ones_like(mean_actions) * log_std.exp() self.distribution = Normal(mean_actions, action_std) return self def log_prob(self, actions: th.Tensor, gaussian_actions: Optional[th.Tensor] = None) -> th.Tensor: # Inverse tanh if gaussian_actions is None: gaussian_actions = th.clamp(actions, min=-1.0 + self.eps, max=1.0 - self.eps) gaussian_actions = 0.5 * (gaussian_actions.log1p() - (-gaussian_actions).log1p()) # Log likelihood for a Gaussian distribution log_prob = self.distribution.log_prob(gaussian_actions) log_prob = sum_independent_dims(log_prob) # sb3 correction # log_prob -= th.sum(th.log(1 - actions ** 2 + self.eps), dim=1) # spinning-up correction log_prob -= (2*(np.log(2) - gaussian_actions - F.softplus(-2*gaussian_actions))).sum(axis=1) return log_prob def entropy(self) -> Optional[th.Tensor]: return None def sample(self) -> th.Tensor: return th.tanh(self.distribution.rsample()) def mode(self) -> th.Tensor: return th.tanh(self.distribution.mean) def get_actions(self, deterministic: bool = False) -> th.Tensor: if deterministic: return self.mode() return self.sample() class BetaDistribution(): def __init__(self, action_dim=2, dist_init=None): assert action_dim == 2 self.distribution = None self.action_dim = action_dim self.dist_init = dist_init self.low = 0.0 self.high = 1.0 # [beta, alpha], [0, 1] self.acc_exploration_dist = { # [1, 2.5] # [1.5, 1.0] 'go': th.FloatTensor([1.0, 2.5]), 'stop': th.FloatTensor([1.5, 1.0]) } self.steer_exploration_dist = { 'turn': th.FloatTensor([1.0, 1.0]), 'straight': th.FloatTensor([3.0, 3.0]) } if th.cuda.is_available(): self.device = 'cuda' else: self.device = 'cpu' def proba_distribution_net(self, latent_dim: int) -> Tuple[nn.Module, nn.Module]: linear_alpha = nn.Linear(latent_dim, self.action_dim) linear_beta = nn.Linear(latent_dim, self.action_dim) if self.dist_init is not None: # linear_alpha.weight.data.fill_(0.01) # linear_beta.weight.data.fill_(0.01) # acc linear_alpha.bias.data[0] = self.dist_init[0][1] linear_beta.bias.data[0] = self.dist_init[0][0] # steer linear_alpha.bias.data[1] = self.dist_init[1][1] linear_beta.bias.data[1] = self.dist_init[1][0] alpha = nn.Sequential(linear_alpha, nn.Softplus()) beta = nn.Sequential(linear_beta, nn.Softplus()) return alpha, beta def proba_distribution(self, alpha, beta): self.distribution = Beta(alpha, beta) return self def log_prob(self, actions: th.Tensor) -> th.Tensor: log_prob = self.distribution.log_prob(actions) return sum_independent_dims(log_prob) def entropy_loss(self) -> th.Tensor: entropy_loss = -1.0 * self.distribution.entropy() return th.mean(entropy_loss) def exploration_loss(self, exploration_suggests) -> th.Tensor: # [('stop'/'go'/None, 'turn'/'straight'/None)] # (batch_size, action_dim) alpha = self.distribution.concentration1.detach().clone() beta = self.distribution.concentration0.detach().clone() for i, (acc_suggest, steer_suggest) in enumerate(exploration_suggests): if acc_suggest != '': beta[i, 0] = self.acc_exploration_dist[acc_suggest][0] alpha[i, 0] = self.acc_exploration_dist[acc_suggest][1] if steer_suggest != '': beta[i, 1] = self.steer_exploration_dist[steer_suggest][0] alpha[i, 1] = self.steer_exploration_dist[steer_suggest][1] dist_ent = Beta(alpha, beta) exploration_loss = th.distributions.kl_divergence(self.distribution, dist_ent) return th.mean(exploration_loss) def sample(self) -> th.Tensor: # Reparametrization trick to pass gradients return self.distribution.rsample() def mode(self) -> th.Tensor: alpha = self.distribution.concentration1 beta = self.distribution.concentration0 x = th.zeros_like(alpha) x[:, 1] += 0.5 mask1 = (alpha > 1) & (beta > 1) x[mask1] = (alpha[mask1]-1)/(alpha[mask1]+beta[mask1]-2) mask2 = (alpha <= 1) & (beta > 1) x[mask2] = 0.0 mask3 = (alpha > 1) & (beta <= 1) x[mask3] = 1.0 # mean mask4 = (alpha <= 1) & (beta <= 1) x[mask4] = self.distribution.mean[mask4] return x def get_actions(self, deterministic: bool = False) -> th.Tensor: if deterministic: return self.mode() return self.sample() ================================================ FILE: roach/models/ppo.py ================================================ import time import torch as th import numpy as np from collections import deque from torch.nn import functional as F from stable_baselines3.common.vec_env import VecEnv from stable_baselines3.common.callbacks import BaseCallback from stable_baselines3.common.utils import explained_variance from .ppo_buffer import PpoBuffer class PPO(): def __init__(self, policy, env, learning_rate: float = 1e-5, n_steps_total: int = 8192, batch_size: int = 256, n_epochs: int = 20, gamma: float = 0.99, gae_lambda: float = 0.9, clip_range: float = 0.2, clip_range_vf: float = None, ent_coef: float = 0.05, explore_coef: float = 0.05, vf_coef: float = 0.5, max_grad_norm: float = 0.5, target_kl: float = 0.01, update_adv=False, lr_schedule_step=None, start_num_timesteps: int = 0): self.policy = policy self.env = env self.learning_rate = learning_rate self.n_steps_total = n_steps_total self.n_steps = n_steps_total//env.num_envs self.batch_size = batch_size self.n_epochs = n_epochs self.gamma = gamma self.gae_lambda = gae_lambda self.clip_range = clip_range self.clip_range_vf = clip_range_vf self.ent_coef = ent_coef self.explore_coef = explore_coef self.vf_coef = vf_coef self.max_grad_norm = max_grad_norm self.target_kl = target_kl self.update_adv = update_adv self.lr_schedule_step = lr_schedule_step self.start_num_timesteps = start_num_timesteps self.num_timesteps = start_num_timesteps self._last_obs = None self._last_dones = None self.ep_stat_buffer = None self.buffer = PpoBuffer(self.n_steps, self.env.observation_space, self.env.action_space, gamma=self.gamma, gae_lambda=self.gae_lambda, n_envs=self.env.num_envs) self.policy = self.policy.to(self.policy.device) model_parameters = filter(lambda p: p.requires_grad, self.policy.parameters()) total_params = sum([np.prod(p.size()) for p in model_parameters]) print(f'trainable parameters: {total_params/1000000:.2f}M') def collect_rollouts(self, env: VecEnv, callback: BaseCallback, rollout_buffer: PpoBuffer, n_rollout_steps: int) -> bool: assert self._last_obs is not None, "No previous observation was provided" n_steps = 0 rollout_buffer.reset() self.action_statistics = [] self.mu_statistics = [] self.sigma_statistics = [] while n_steps < n_rollout_steps: actions, values, log_probs, mu, sigma, _ = self.policy.forward(self._last_obs) self.action_statistics.append(actions) self.mu_statistics.append(mu) self.sigma_statistics.append(sigma) new_obs, rewards, dones, infos = env.step(actions) if callback.on_step() is False: return False # update_info_buffer for i in np.where(dones)[0]: self.ep_stat_buffer.append(infos[i]['episode_stat']) n_steps += 1 self.num_timesteps += env.num_envs rollout_buffer.add(self._last_obs, actions, rewards, self._last_dones, values, log_probs, mu, sigma, infos) self._last_obs = new_obs self._last_dones = dones last_values = self.policy.forward_value(self._last_obs) rollout_buffer.compute_returns_and_advantage(last_values, dones=self._last_dones) return True def train(self): for param_group in self.policy.optimizer.param_groups: param_group["lr"] = self.learning_rate entropy_losses, exploration_losses, pg_losses, value_losses, losses = [], [], [], [], [] clip_fractions = [] approx_kl_divs = [] # train for gradient_steps epochs epoch = 0 data_len = int(self.buffer.buffer_size * self.buffer.n_envs / self.batch_size) for epoch in range(self.n_epochs): approx_kl_divs = [] # Do a complete pass on the rollout buffer self.buffer.start_caching(self.batch_size) # while self.buffer.sample_queue.qsize() < 3: # time.sleep(0.01) for i in range(data_len): if self.buffer.sample_queue.empty(): while self.buffer.sample_queue.empty(): # print(f'buffer_empty: {self.buffer.sample_queue.qsize()}') time.sleep(0.01) rollout_data = self.buffer.sample_queue.get() values, log_prob, entropy_loss, exploration_loss, distribution = self.policy.evaluate_actions( rollout_data.observations, rollout_data.actions, rollout_data.exploration_suggests, detach_values=False) # Normalize advantage advantages = rollout_data.advantages # advantages = (advantages - advantages.mean()) / (advantages.std() + 1e-8) # ratio between old and new policy, should be one at the first iteration ratio = th.exp(log_prob - rollout_data.old_log_prob) # clipped surrogate loss policy_loss_1 = advantages * ratio policy_loss_2 = advantages * th.clamp(ratio, 1 - self.clip_range, 1 + self.clip_range) policy_loss = -th.min(policy_loss_1, policy_loss_2).mean() # Logging clip_fraction = th.mean((th.abs(ratio - 1) > self.clip_range).float()).item() clip_fractions.append(clip_fraction) if self.clip_range_vf is None: # No clipping values_pred = values else: # Clip the different between old and new value # NOTE: this depends on the reward scaling values_pred = rollout_data.old_values + th.clamp(values - rollout_data.old_values, -self.clip_range_vf, self.clip_range_vf) # Value loss using the TD(gae_lambda) target value_loss = F.mse_loss(rollout_data.returns, values_pred) loss = policy_loss + self.vf_coef * value_loss \ + self.ent_coef * entropy_loss + self.explore_coef * exploration_loss losses.append(loss.item()) pg_losses.append(policy_loss.item()) value_losses.append(value_loss.item()) entropy_losses.append(entropy_loss.item()) exploration_losses.append(exploration_loss.item()) # Optimization step self.policy.optimizer.zero_grad() loss.backward() # Clip grad norm th.nn.utils.clip_grad_norm_(self.policy.parameters(), self.max_grad_norm) self.policy.optimizer.step() with th.no_grad(): old_distribution = self.policy.action_dist.proba_distribution( rollout_data.old_mu, rollout_data.old_sigma) kl_div = th.distributions.kl_divergence(old_distribution.distribution, distribution) approx_kl_divs.append(kl_div.mean().item()) if self.target_kl is not None and np.mean(approx_kl_divs) > 1.5 * self.target_kl: if self.lr_schedule_step is not None: self.kl_early_stop += 1 if self.kl_early_stop >= self.lr_schedule_step: self.learning_rate *= 0.5 self.kl_early_stop = 0 break # update advantages if self.update_adv: self.buffer.update_values(self.policy) last_values = self.policy.forward_value(self._last_obs) self.buffer.compute_returns_and_advantage(last_values, dones=self._last_dones) explained_var = explained_variance(self.buffer.returns.flatten(), self.buffer.values.flatten()) # Logs self.train_debug = { "train/entropy_loss": np.mean(entropy_losses), "train/exploration_loss": np.mean(exploration_losses), "train/policy_gradient_loss": np.mean(pg_losses), "train/value_loss": np.mean(value_losses), "train/last_epoch_kl": np.mean(approx_kl_divs), "train/clip_fraction": np.mean(clip_fractions), "train/loss": np.mean(losses), "train/explained_variance": explained_var, "train/clip_range": self.clip_range, "train/train_epoch": epoch, "train/learning_rate": self.learning_rate } def learn(self, total_timesteps, callback=None, seed=2021): # reset env seed self.env.action_space.seed(seed) self.env.observation_space.seed(seed) self.env.seed(seed) self.start_time = time.time() self.kl_early_stop = 0 self.t_train_values = 0.0 self.ep_stat_buffer = deque(maxlen=100) self._last_obs = self.env.reset() self._last_dones = np.zeros((self.env.num_envs,), dtype=np.bool) callback.init_callback(self) callback.on_training_start(locals(), globals()) while self.num_timesteps < total_timesteps: callback.on_rollout_start() t0 = time.time() self.policy = self.policy.train() continue_training = self.collect_rollouts(self.env, callback, self.buffer, self.n_steps) self.t_rollout = time.time() - t0 callback.on_rollout_end() if continue_training is False: break t0 = time.time() self.train() self.t_train = time.time() - t0 callback.on_training_end() return self def _get_init_kwargs(self): init_kwargs = dict( learning_rate=self.learning_rate, n_steps_total=self.n_steps_total, batch_size=self.batch_size, n_epochs=self.n_epochs, gamma=self.gamma, gae_lambda=self.gae_lambda, clip_range=self.clip_range, clip_range_vf=self.clip_range_vf, ent_coef=self.ent_coef, explore_coef=self.explore_coef, vf_coef=self.vf_coef, max_grad_norm=self.max_grad_norm, target_kl=self.target_kl, update_adv=self.update_adv, lr_schedule_step=self.lr_schedule_step, start_num_timesteps=self.num_timesteps, ) return init_kwargs def save(self, path: str) -> None: th.save({'policy_state_dict': self.policy.state_dict(), 'policy_init_kwargs': self.policy.get_init_kwargs(), 'train_init_kwargs': self._get_init_kwargs()}, path) def get_env(self): return self.env ================================================ FILE: roach/models/ppo_buffer.py ================================================ from gym import spaces import numpy as np from typing import Optional, Generator, NamedTuple, Dict, List import torch as th from stable_baselines3.common.vec_env.base_vec_env import tile_images import cv2 import time from threading import Thread import queue COLORS = [ [46, 52, 54], [136, 138, 133], [255, 0, 255], [0, 255, 255], [0, 0, 255], [255, 0, 0], [255, 255, 0], [255, 255, 255] ] class PpoBufferSamples(NamedTuple): observations: Dict[str, th.Tensor] actions: th.Tensor old_values: th.Tensor old_log_prob: th.Tensor old_mu: th.Tensor old_sigma: th.Tensor advantages: th.Tensor returns: th.Tensor exploration_suggests: List[tuple] class PpoBuffer(): def __init__(self, buffer_size: int, observation_space: spaces.Space, action_space: spaces.Space, gae_lambda: float = 1, gamma: float = 0.99, n_envs: int = 1): self.buffer_size = buffer_size self.observation_space = observation_space self.action_space = action_space self.gae_lambda = gae_lambda self.gamma = gamma self.n_envs = n_envs self.reset() self.pos = 0 self.full = False if th.cuda.is_available(): self.device = 'cuda' else: self.device = 'cpu' self.sample_queue = queue.Queue() def reset(self) -> None: self.observations = {} for k, s in self.observation_space.spaces.items(): self.observations[k] = np.zeros((self.buffer_size, self.n_envs,)+s.shape, dtype=s.dtype) # int(np.prod(self.action_space.shape)) self.actions = np.zeros((self.buffer_size, self.n_envs)+self.action_space.shape, dtype=np.float32) self.rewards = np.zeros((self.buffer_size, self.n_envs), dtype=np.float32) self.returns = np.zeros((self.buffer_size, self.n_envs), dtype=np.float32) self.advantages = np.zeros((self.buffer_size, self.n_envs), dtype=np.float32) self.dones = np.zeros((self.buffer_size, self.n_envs), dtype=np.float32) self.values = np.zeros((self.buffer_size, self.n_envs), dtype=np.float32) self.log_probs = np.zeros((self.buffer_size, self.n_envs), dtype=np.float32) self.mus = np.zeros((self.buffer_size, self.n_envs)+self.action_space.shape, dtype=np.float32) self.sigmas = np.zeros((self.buffer_size, self.n_envs)+self.action_space.shape, dtype=np.float32) self.exploration_suggests = np.zeros((self.buffer_size, self.n_envs), dtype=[('acc', 'U10'), ('steer', 'U10')]) self.reward_debugs = [[] for i in range(self.n_envs)] self.terminal_debugs = [[] for i in range(self.n_envs)] self.pos = 0 self.full = False def compute_returns_and_advantage(self, last_value: th.Tensor, dones: np.ndarray) -> None: last_gae_lam = 0 for step in reversed(range(self.buffer_size)): if step == self.buffer_size - 1: next_non_terminal = 1.0 - dones next_value = last_value # spinning up return calculation # self.returns[step] = self.rewards[step] + self.gamma * last_value * next_non_terminal else: next_non_terminal = 1.0 - self.dones[step + 1] next_value = self.values[step + 1] # spinning up return calculation # self.returns[step] = self.rewards[step] + self.gamma * self.returns[step+1] * next_non_terminal delta = self.rewards[step] + self.gamma * next_value * next_non_terminal - self.values[step] last_gae_lam = delta + self.gamma * self.gae_lambda * next_non_terminal * last_gae_lam self.advantages[step] = last_gae_lam # sb3 return self.returns = self.advantages + self.values def add(self, obs_dict: Dict[str, np.ndarray], action: np.ndarray, reward: np.ndarray, done: np.ndarray, value: np.ndarray, log_prob: np.ndarray, mu: np.ndarray, sigma: np.ndarray, infos) -> None: for k, v in obs_dict.items(): self.observations[k][self.pos] = v self.actions[self.pos] = action self.rewards[self.pos] = reward self.dones[self.pos] = done self.values[self.pos] = value self.log_probs[self.pos] = log_prob self.mus[self.pos] = mu self.sigmas[self.pos] = sigma for i in range(self.n_envs): self.reward_debugs[i].append(infos[i]['reward_debug']['debug_texts']) self.terminal_debugs[i].append(infos[i]['terminal_debug']['debug_texts']) n_steps = infos[i]['terminal_debug']['exploration_suggest']['n_steps'] if n_steps > 0: n_start = max(0, self.pos-n_steps) self.exploration_suggests[n_start:self.pos, i] = \ infos[i]['terminal_debug']['exploration_suggest']['suggest'] self.pos += 1 if self.pos == self.buffer_size: self.full = True def update_values(self, policy): for i in range(self.buffer_size): obs_dict = {} for k in self.observations.keys(): obs_dict[k] = self.observations[k][i] values = policy.forward_value(obs_dict) self.values[i] = values def get(self, batch_size: Optional[int] = None) -> Generator[PpoBufferSamples, None, None]: assert self.full, '' indices = np.random.permutation(self.buffer_size * self.n_envs) # Prepare the data for tensor in ['actions', 'values', 'log_probs', 'advantages', 'returns', 'mus', 'sigmas', 'exploration_suggests']: self.__dict__['flat_'+tensor] = self.flatten(self.__dict__[tensor]) self.flat_observations = {} for k in self.observations.keys(): self.flat_observations[k] = self.flatten(self.observations[k]) # spinning up: the next two lines implement the advantage normalization trick adv_mean = np.mean(self.advantages) adv_std = np.std(self.advantages) + np.finfo(np.float32).eps self.advantages = (self.advantages - adv_mean) / adv_std # Return everything, don't create minibatches if batch_size is None: batch_size = self.buffer_size * self.n_envs start_idx = 0 while start_idx < self.buffer_size * self.n_envs: yield self._get_samples(indices[start_idx:start_idx + batch_size]) start_idx += batch_size def _get_samples(self, batch_inds: np.ndarray) -> PpoBufferSamples: def to_torch(x): return th.as_tensor(x).to(self.device) # return th.from_numpy(x.astype(np.float32)).to(self.device) obs_dict = {} for k in self.observations.keys(): obs_dict[k] = to_torch(self.flat_observations[k][batch_inds]) data = (self.flat_actions[batch_inds], self.flat_values[batch_inds], self.flat_log_probs[batch_inds], self.flat_mus[batch_inds], self.flat_sigmas[batch_inds], self.flat_advantages[batch_inds], self.flat_returns[batch_inds] ) data_torch = (obs_dict,) + tuple(map(to_torch, data)) + (self.flat_exploration_suggests[batch_inds],) return PpoBufferSamples(*data_torch) @staticmethod def flatten(arr: np.ndarray) -> np.ndarray: shape = arr.shape # if len(shape) < 3: # return arr.swapaxes(0, 1).reshape(shape[0] * shape[1]) # else: return arr.reshape(shape[0] * shape[1], *shape[2:]) def render(self): assert self.full, '' list_render = [] _, _, c, h, w = self.observations['birdview'].shape vis_idx = np.array([0, 1, 2, 6, 10, 14]) for i in range(self.buffer_size): im_envs = [] for j in range(self.n_envs): masks = self.observations['birdview'][i, j, vis_idx, :, :] > 100 im_birdview = np.zeros([h, w, 3], dtype=np.uint8) for idx_c in range(len(vis_idx)): im_birdview[masks[idx_c]] = COLORS[idx_c] im = np.zeros([h, w*2, 3], dtype=np.uint8) im[:h, :w] = im_birdview action_str = np.array2string(self.actions[i, j], precision=1, separator=',', suppress_small=True) state_str = np.array2string(self.observations['state'][i, j], precision=1, separator=',', suppress_small=True) reward = self.rewards[i, j] ret = self.returns[i, j] advantage = self.advantages[i, j] done = int(self.dones[i, j]) value = self.values[i, j] log_prob = self.log_probs[i, j] txt_1 = f'v:{value:5.2f} p:{log_prob:5.2f} a{action_str}' im = cv2.putText(im, txt_1, (2, 12), cv2.FONT_HERSHEY_SIMPLEX, 0.35, (255, 255, 255), 1) txt_2 = f'{done} {state_str}' im = cv2.putText(im, txt_2, (2, 24), cv2.FONT_HERSHEY_SIMPLEX, 0.35, (255, 255, 255), 1) txt_3 = f'rw:{reward:5.2f} rt:{ret:5.2f} a:{advantage:5.2f}' im = cv2.putText(im, txt_3, (2, 36), cv2.FONT_HERSHEY_SIMPLEX, 0.35, (255, 255, 255), 1) for i_txt, txt in enumerate(self.reward_debugs[j][i] + self.terminal_debugs[j][i]): im = cv2.putText(im, txt, (w, (i_txt+1)*15), cv2.FONT_HERSHEY_SIMPLEX, 0.35, (255, 255, 255), 1) im_envs.append(im) big_im = tile_images(im_envs) list_render.append(big_im) return list_render def start_caching(self, batch_size): thread1 = Thread(target=self.cache_to_cuda, args=(batch_size,)) thread1.start() def cache_to_cuda(self, batch_size): self.sample_queue.queue.clear() for rollout_data in self.get(batch_size): while self.sample_queue.qsize() >= 2: time.sleep(0.01) self.sample_queue.put(rollout_data) def size(self) -> int: """ :return: (int) The current size of the buffer """ if self.full: return self.buffer_size return self.pos ================================================ FILE: roach/models/ppo_policy.py ================================================ from typing import Union, Dict, Tuple, Any from functools import partial import gym import torch as th import torch.nn as nn import numpy as np from roach.utils.config_utils import load_entry_point class PpoPolicy(nn.Module): def __init__(self, observation_space: gym.spaces.Space, action_space: gym.spaces.Space, policy_head_arch=[256, 256], value_head_arch=[256, 256], features_extractor_entry_point=None, features_extractor_kwargs={}, distribution_entry_point=None, distribution_kwargs={}): super(PpoPolicy, self).__init__() self.observation_space = observation_space self.action_space = action_space self.features_extractor_entry_point = features_extractor_entry_point self.features_extractor_kwargs = features_extractor_kwargs self.distribution_entry_point = distribution_entry_point self.distribution_kwargs = distribution_kwargs if th.cuda.is_available(): self.device = 'cuda' else: self.device = 'cpu' self.optimizer_class = th.optim.Adam self.optimizer_kwargs = {'eps': 1e-5} features_extractor_entry_point = features_extractor_entry_point.replace("agents.rl_birdview","roach") features_extractor_class = load_entry_point(features_extractor_entry_point) self.features_extractor = features_extractor_class(observation_space, **features_extractor_kwargs) distribution_entry_point = distribution_entry_point.replace("agents.rl_birdview","roach") distribution_class = load_entry_point(distribution_entry_point) self.action_dist = distribution_class(int(np.prod(action_space.shape)), **distribution_kwargs) if 'StateDependentNoiseDistribution' in distribution_entry_point: self.use_sde = True self.sde_sample_freq = 4 else: self.use_sde = False self.sde_sample_freq = None # best_so_far # self.net_arch = [dict(pi=[256, 128, 64], vf=[128, 64])] self.policy_head_arch = list(policy_head_arch) self.value_head_arch = list(value_head_arch) self.activation_fn = nn.ReLU self.ortho_init = False self._build() def reset_noise(self, n_envs: int = 1) -> None: assert self.use_sde, 'reset_noise() is only available when using gSDE' self.action_dist.sample_weights(self.dist_sigma, batch_size=n_envs) def _build(self) -> None: last_layer_dim_pi = self.features_extractor.features_dim policy_net = [] for layer_size in self.policy_head_arch: policy_net.append(nn.Linear(last_layer_dim_pi, layer_size)) policy_net.append(self.activation_fn()) last_layer_dim_pi = layer_size self.policy_head = nn.Sequential(*policy_net).to(self.device) # mu->alpha/mean, sigma->beta/log_std (nn.Module, nn.Parameter) self.dist_mu, self.dist_sigma = self.action_dist.proba_distribution_net(last_layer_dim_pi) last_layer_dim_vf = self.features_extractor.features_dim value_net = [] for layer_size in self.value_head_arch: value_net.append(nn.Linear(last_layer_dim_vf, layer_size)) value_net.append(self.activation_fn()) last_layer_dim_vf = layer_size value_net.append(nn.Linear(last_layer_dim_vf, 1)) self.value_head = nn.Sequential(*value_net).to(self.device) # Init weights: use orthogonal initialization # with small initial weight for the output if self.ortho_init: # check for features_extractor # Values from stable-baselines. # feature_extractor/mlp values are # originally from openai/baselines (default gains/init_scales). module_gains = { # self.features_extractor: np.sqrt(2), self.policy_head: np.sqrt(2), self.value_head: np.sqrt(2) # self.action_net: 0.01, } for module, gain in module_gains.items(): module.apply(partial(self.init_weights, gain=gain)) self.optimizer = self.optimizer_class(self.parameters(), **self.optimizer_kwargs) def _get_features(self, birdview: th.Tensor, state: th.Tensor) -> th.Tensor: """ :param birdview: th.Tensor (num_envs, frame_stack*channel, height, width) :param state: th.Tensor (num_envs, state_dim) """ birdview = birdview.float() / 255.0 features, cnn_feature = self.features_extractor(birdview, state) return features, cnn_feature def _get_action_dist_from_features(self, features: th.Tensor): latent_pi = self.policy_head(features) mu = self.dist_mu(latent_pi) if isinstance(self.dist_sigma, nn.Parameter): sigma = self.dist_sigma else: sigma = self.dist_sigma(latent_pi) return self.action_dist.proba_distribution(mu, sigma), mu.detach().cpu().numpy(), sigma.detach().cpu().numpy() def evaluate_actions(self, obs_dict: Dict[str, th.Tensor], actions: th.Tensor, exploration_suggests, detach_values=False): features, cnn_feature = self._get_features(**obs_dict) if detach_values: detached_features = features.detach() values = self.value_head(detached_features) else: values = self.value_head(features) distribution, mu, sigma = self._get_action_dist_from_features(features) actions = self.scale_action(actions) log_prob = distribution.log_prob(actions) return values.flatten(), log_prob, distribution.entropy_loss(), \ distribution.exploration_loss(exploration_suggests), distribution.distribution def evaluate_values(self, obs_dict: Dict[str, th.Tensor]): features, cnn_feature = self._get_features(**obs_dict) values = self.value_head(features) distribution, mu, sigma = self._get_action_dist_from_features(features) return values.flatten(), distribution.distribution def forward(self, obs_dict: Dict[str, np.ndarray], deterministic: bool = False, clip_action: bool = False, only_feature: bool = False, feature_input: np.ndarray = None): ''' used in collect_rollouts(), do not clamp actions ''' with th.no_grad(): if feature_input is None: obs_tensor_dict = dict([(k, th.as_tensor(v).to(self.device).unsqueeze(0)) for k, v in obs_dict.items()]) features, cnn_feature = self._get_features(**obs_tensor_dict) else: features = th.tensor(feature_input).to(self.device) if only_feature: return features.cpu().numpy() values = self.value_head(features) distribution, mu, sigma = self._get_action_dist_from_features(features) actions = distribution.get_actions(deterministic=deterministic) log_prob = distribution.log_prob(actions) actions = actions.cpu().numpy() actions = self.unscale_action(actions) if clip_action: actions = np.clip(actions, self.action_space.low, self.action_space.high) values = values.cpu().numpy().flatten() log_prob = log_prob.cpu().numpy() features = features.cpu().numpy() return actions, values, log_prob, mu, sigma, features, cnn_feature def forward_value(self, obs_dict: Dict[str, np.ndarray]) -> np.ndarray: with th.no_grad(): obs_tensor_dict = dict([(k, th.as_tensor(v).to(self.device)) for k, v in obs_dict.items()]) features, cnn_feature = self._get_features(**obs_tensor_dict) values = self.value_head(features) values = values.cpu().numpy().flatten() return values def forward_policy(self, obs_dict: Dict[str, np.ndarray]) -> np.ndarray: with th.no_grad(): obs_tensor_dict = dict([(k, th.as_tensor(v).to(self.device)) for k, v in obs_dict.items()]) features, cnn_feature = self._get_features(**obs_tensor_dict) distribution, mu, sigma = self._get_action_dist_from_features(features) return mu, sigma def scale_action(self, action: th.Tensor, eps=1e-7) -> th.Tensor: # input action \in [a_low, a_high] # output action \in [d_low+eps, d_high-eps] d_low, d_high = self.action_dist.low, self.action_dist.high # scalar if d_low is not None and d_high is not None: a_low = th.as_tensor(self.action_space.low.astype(np.float32)).to(action.device) a_high = th.as_tensor(self.action_space.high.astype(np.float32)).to(action.device) action = (action-a_low)/(a_high-a_low) * (d_high-d_low) + d_low action = th.clamp(action, d_low+eps, d_high-eps) return action def unscale_action(self, action: np.ndarray, eps=0.0) -> np.ndarray: # input action \in [d_low, d_high] # output action \in [a_low+eps, a_high-eps] d_low, d_high = self.action_dist.low, self.action_dist.high # scalar if d_low is not None and d_high is not None: # batch_size = action.shape[0] a_low, a_high = self.action_space.low, self.action_space.high # same shape as action [batch_size, action_dim] # a_high = np.tile(self.action_space.high, [batch_size, 1]) action = (action-d_low)/(d_high-d_low) * (a_high-a_low) + a_low # action = np.clip(action, a_low+eps, a_high-eps) return action def get_init_kwargs(self) -> Dict[str, Any]: init_kwargs = dict( observation_space=self.observation_space, action_space=self.action_space, policy_head_arch=self.policy_head_arch, value_head_arch=self.value_head_arch, features_extractor_entry_point=self.features_extractor_entry_point, features_extractor_kwargs=self.features_extractor_kwargs, distribution_entry_point=self.distribution_entry_point, distribution_kwargs=self.distribution_kwargs, ) return init_kwargs @classmethod def load(cls, path): if th.cuda.is_available(): device = 'cuda' else: device = 'cpu' saved_variables = th.load(path, map_location=device) # Create policy object model = cls(**saved_variables['policy_init_kwargs']) state_dict = saved_variables['policy_state_dict'] for index in [2, 4, 6, 8, 10]: state_dict["features_extractor.cnn."+str(index//2)+".weight"] = state_dict.pop("features_extractor.cnn."+str(index)+".weight") state_dict["features_extractor.cnn."+str(index//2)+".bias"] = state_dict.pop("features_extractor.cnn."+str(index)+".bias") #OLD!!! odict_keys(['features_extractor.cnn.0.weight', 'features_extractor.cnn.0.bias', 'features_extractor.cnn.2.weight', 'features_extractor.cnn.2.bias', 'features_extractor.cnn.4.weight', 'features_extractor.cnn.4.bias', 'features_extractor.cnn.6.weight', 'features_extractor.cnn.6.bias', 'features_extractor.cnn.8.weight', 'features_extractor.cnn.8.bias', 'features_extractor.cnn.10.weight', 'features_extractor.cnn.10.bias', 'features_extractor.linear.0.weight', 'features_extractor.linear.0.bias', 'features_extractor.linear.2.weight', 'features_extractor.linear.2.bias', 'features_extractor.state_linear.0.weight', 'features_extractor.state_linear.0.bias', 'features_extractor.state_linear.2.weight', 'features_extractor.state_linear.2.bias', 'policy_head.0.weight', 'policy_head.0.bias', 'policy_head.2.weight', 'policy_head.2.bias', 'dist_mu.0.weight', 'dist_mu.0.bias', 'dist_sigma.0.weight', 'dist_sigma.0.bias', 'value_head.0.weight', 'value_head.0.bias', 'value_head.2.weight', 'value_head.2.bias', 'value_head.4.weight', 'value_head.4.bias']) # odict_keys(['features_extractor.cnn.0.weight', 'features_extractor.cnn.0.bias', 'features_extractor.cnn.1.weight', 'features_extractor.cnn.1.bias', 'features_extractor.cnn.2.weight', 'features_extractor.cnn.2.bias', 'features_extractor.cnn.3.weight', 'features_extractor.cnn.3.bias', 'features_extractor.cnn.4.weight', 'features_extractor.cnn.4.bias', 'features_extractor.cnn.5.weight', 'features_extractor.cnn.5.bias', 'features_extractor.linear.0.weight', 'features_extractor.linear.0.bias', 'features_extractor.linear.2.weight', 'features_extractor.linear.2.bias', 'features_extractor.state_linear.0.weight', 'features_extractor.state_linear.0.bias', 'features_extractor.state_linear.2.weight', 'features_extractor.state_linear.2.bias', 'policy_head.0.weight', 'policy_head.0.bias', 'policy_head.2.weight', 'policy_head.2.bias', 'dist_mu.0.weight', 'dist_mu.0.bias', 'dist_sigma.0.weight', 'dist_sigma.0.bias', 'value_head.0.weight', 'value_head.0.bias', 'value_head.2.weight', 'value_head.2.bias', 'value_head.4.weight', 'value_head.4.bias']) # Load weights model.load_state_dict(saved_variables['policy_state_dict']) model.to(device) return model, saved_variables['train_init_kwargs'] @staticmethod def init_weights(module: nn.Module, gain: float = 1) -> None: """ Orthogonal initialization (used in PPO and A2C) """ if isinstance(module, (nn.Linear, nn.Conv2d)): nn.init.orthogonal_(module.weight, gain=gain) if module.bias is not None: module.bias.data.fill_(0.0) ================================================ FILE: roach/models/torch_layers.py ================================================ """Policies: abstract base class and concrete implementations.""" import torch as th import torch.nn as nn import numpy as np from . import torch_util as tu class XtMaCNN(nn.Module): ''' Inspired by https://github.com/xtma/pytorch_car_caring ''' def __init__(self, observation_space, features_dim=256, states_neurons=[256]): super().__init__() self.features_dim = features_dim n_input_channels = observation_space['birdview'].shape[0] self.cnn = nn.ModuleList([ nn.Conv2d(n_input_channels, 8, kernel_size=5, stride=2), #nn.ReLU(), nn.Conv2d(8, 16, kernel_size=5, stride=2), #nn.ReLU(), nn.Conv2d(16, 32, kernel_size=5, stride=2), #nn.ReLU(), nn.Conv2d(32, 64, kernel_size=3, stride=2), #nn.ReLU(), nn.Conv2d(64, 128, kernel_size=3, stride=2), #nn.ReLU(), nn.Conv2d(128, 256, kernel_size=3, stride=1),] #nn.ReLU(), #nn.Flatten(), ) self.relu = nn.ReLU() # self.cnn = nn.ModuleList( # nn.Conv2d(n_input_channels, 8, kernel_size=5, stride=2), # nn.ReLU(), # nn.Conv2d(8, 16, kernel_size=5, stride=2), # nn.ReLU(), # nn.Conv2d(16, 32, kernel_size=5, stride=2), # nn.ReLU(), # nn.Conv2d(32, 64, kernel_size=3, stride=2), # nn.ReLU(), # nn.Conv2d(64, 128, kernel_size=3, stride=2), # nn.ReLU(), # nn.Conv2d(128, 256, kernel_size=3, stride=1), # nn.ReLU(), # #nn.Flatten(), # ) # Compute shape by doing one forward pass #with th.no_grad(): #n_flatten = self.cnn(th.as_tensor(observation_space['birdview'].sample()[None]).float()).flatten(start_dim=1).shape[1] n_flatten = 1024 self.linear = nn.Sequential(nn.Linear(n_flatten+states_neurons[-1], 512), nn.ReLU(), nn.Linear(512, features_dim), nn.ReLU()) states_neurons = [observation_space['state'].shape[0]] + states_neurons self.state_linear = [] for i in range(len(states_neurons)-1): self.state_linear.append(nn.Linear(states_neurons[i], states_neurons[i+1])) self.state_linear.append(nn.ReLU()) self.state_linear = nn.Sequential(*self.state_linear) self.apply(self._weights_init) @staticmethod def _weights_init(m): if isinstance(m, nn.Conv2d): nn.init.xavier_uniform_(m.weight, gain=nn.init.calculate_gain('relu')) nn.init.constant_(m.bias, 0.1) def forward(self, birdview, state): cnn_feature = [] feature = birdview for i in range(len(self.cnn)): feature = self.relu(self.cnn[i](feature)) if birdview.shape[0] == 1: cnn_feature.append(feature[0, ...].detach().cpu().numpy()) #cnn_feature = self.cnn(birdview) x = feature.flatten(start_dim=1) latent_state = self.state_linear(state) # latent_state = state.repeat(1, state.shape[1]*256) x = th.cat((x, latent_state), dim=1) x = self.linear(x) return x, cnn_feature class ImpalaCNN(nn.Module): def __init__(self, observation_space, chans=(16, 32, 32, 64, 64), states_neurons=[256], features_dim=256, nblock=2, batch_norm=False, final_relu=True): # (16, 32, 32) super().__init__() self.features_dim = features_dim self.final_relu = final_relu # image encoder curshape = observation_space['birdview'].shape s = 1 / np.sqrt(len(chans)) # per stack scale self.stacks = nn.ModuleList() for outchan in chans: stack = tu.CnnDownStack(curshape[0], nblock=nblock, outchan=outchan, scale=s, batch_norm=batch_norm) self.stacks.append(stack) curshape = stack.output_shape(curshape) # dense after concatenate n_image_latent = tu.intprod(curshape) self.dense = tu.NormedLinear(n_image_latent+states_neurons[-1], features_dim, scale=1.4) # state encoder states_neurons = [observation_space['state'].shape[0]] + states_neurons self.state_linear = [] for i in range(len(states_neurons)-1): self.state_linear.append(tu.NormedLinear(states_neurons[i], states_neurons[i+1])) self.state_linear.append(nn.ReLU()) self.state_linear = nn.Sequential(*self.state_linear) def forward(self, birdview, state): # birdview: [b, c, h, w] # x = x.to(dtype=th.float32) / self.scale_ob for layer in self.stacks: birdview = layer(birdview) x = th.flatten(birdview, 1) x = th.relu(x) latent_state = self.state_linear(state) x = th.cat((x, latent_state), dim=1) x = self.dense(x) if self.final_relu: x = th.relu(x) return x ================================================ FILE: roach/models/torch_util.py ================================================ import torch as th from torch import nn import math import torch.nn.functional as F def NormedLinear(*args, scale=1.0, dtype=th.float32, **kwargs): """ nn.Linear but with normalized fan-in init """ out = nn.Linear(*args, **kwargs) out.weight.data *= scale / out.weight.norm(dim=1, p=2, keepdim=True) if kwargs.get("bias", True): out.bias.data *= 0 return out def NormedConv2d(*args, scale=1, **kwargs): """ nn.Conv2d but with normalized fan-in init """ out = nn.Conv2d(*args, **kwargs) out.weight.data *= scale / out.weight.norm(dim=(1, 2, 3), p=2, keepdim=True) if kwargs.get("bias", True): out.bias.data *= 0 return out def intprod(xs): """ Product of a sequence of integers """ out = 1 for x in xs: out *= x return out class CnnBasicBlock(nn.Module): """ Residual basic block (without batchnorm), as in ImpalaCNN Preserves channel number and shape """ def __init__(self, inchan, scale=1, batch_norm=False): super().__init__() self.inchan = inchan self.batch_norm = batch_norm s = math.sqrt(scale) self.conv0 = NormedConv2d(self.inchan, self.inchan, 3, padding=1, scale=s) self.conv1 = NormedConv2d(self.inchan, self.inchan, 3, padding=1, scale=s) if self.batch_norm: self.bn0 = nn.BatchNorm2d(self.inchan) self.bn1 = nn.BatchNorm2d(self.inchan) def residual(self, x): # inplace should be False for the first relu, so that it does not change the input, # which will be used for skip connection. # getattr is for backwards compatibility with loaded models if getattr(self, "batch_norm", False): x = self.bn0(x) x = F.relu(x, inplace=False) x = self.conv0(x) if getattr(self, "batch_norm", False): x = self.bn1(x) x = F.relu(x, inplace=True) x = self.conv1(x) return x def forward(self, x): return x + self.residual(x) class CnnDownStack(nn.Module): """ Downsampling stack from Impala CNN """ def __init__(self, inchan, nblock, outchan, scale=1, pool=True, **kwargs): super().__init__() self.inchan = inchan self.outchan = outchan self.pool = pool self.firstconv = NormedConv2d(inchan, outchan, 3, padding=1) s = scale / math.sqrt(nblock) self.blocks = nn.ModuleList( [CnnBasicBlock(outchan, scale=s, **kwargs) for _ in range(nblock)] ) def forward(self, x): x = self.firstconv(x) if getattr(self, "pool", True): x = F.max_pool2d(x, kernel_size=3, stride=2, padding=1) for block in self.blocks: x = block(x) return x def output_shape(self, inshape): c, h, w = inshape assert c == self.inchan if getattr(self, "pool", True): return (self.outchan, (h + 1) // 2, (w + 1) // 2) else: return (self.outchan, h, w) ================================================ FILE: roach/obs_manager/actor_state/control.py ================================================ import numpy as np from gym import spaces from roach.obs_manager.obs_manager import ObsManagerBase class ObsManager(): def __init__(self, obs_configs): self._parent_actor = None def attach_ego_vehicle(self, parent_actor): self._parent_actor = parent_actor def get_observation(self): control = self._parent_actor.vehicle.get_control() speed_limit = self._parent_actor.vehicle.get_speed_limit() / 3.6 * 0.8 obs = { 'throttle': np.array([control.throttle], dtype=np.float32), 'steer': np.array([control.steer], dtype=np.float32), 'brake': np.array([control.brake], dtype=np.float32), 'gear': np.array([control.gear], dtype=np.float32), 'speed_limit': np.array([speed_limit], dtype=np.float32), } return obs def clean(self): self._parent_actor = None ================================================ FILE: roach/obs_manager/actor_state/route.py ================================================ import numpy as np from gym import spaces from carla_gym.core.obs_manager.obs_manager import ObsManagerBase import carla_gym.utils.transforms as trans_utils class ObsManager(ObsManagerBase): def __init__(self, obs_configs): self._parent_actor = None self._route_steps = 5 super(ObsManager, self).__init__() def _define_obs_space(self): self.obs_space = spaces.Dict({ 'lateral_dist': spaces.Box(low=0.0, high=2.0, shape=(1,), dtype=np.float32), 'angle_diff': spaces.Box(low=-2.0, high=2.0, shape=(1,), dtype=np.float32), 'route_locs': spaces.Box(low=-5.0, high=5.0, shape=(self._route_steps*2,), dtype=np.float32), 'dist_remaining': spaces.Box(low=0.0, high=100, shape=(1,), dtype=np.float32) }) def attach_ego_vehicle(self, parent_actor): self._parent_actor = parent_actor def get_observation(self): ev_transform = self._parent_actor.vehicle.get_transform() route_plan = self._parent_actor.route_plan # lateral_dist waypoint, road_option = route_plan[0] wp_transform = waypoint.transform d_vec = ev_transform.location - wp_transform.location np_d_vec = np.array([d_vec.x, d_vec.y], dtype=np.float32) wp_unit_forward = wp_transform.rotation.get_forward_vector() np_wp_unit_right = np.array([-wp_unit_forward.y, wp_unit_forward.x], dtype=np.float32) lateral_dist = np.abs(np.dot(np_wp_unit_right, np_d_vec)) lateral_dist = np.clip(lateral_dist, 0, 2) # angle_diff angle_diff = np.deg2rad(np.abs(trans_utils.cast_angle(ev_transform.rotation.yaw - wp_transform.rotation.yaw))) angle_diff = np.clip(angle_diff, -2, 2) # route_locs location_list = [] route_length = len(route_plan) for i in range(self._route_steps): if i < route_length: waypoint, road_option = route_plan[i] else: waypoint, road_option = route_plan[-1] wp_location_world_coord = waypoint.transform.location wp_location_actor_coord = trans_utils.loc_global_to_ref(wp_location_world_coord, ev_transform) location_list += [wp_location_actor_coord.x, wp_location_actor_coord.y] # dist_remaining_in_km dist_remaining_in_km = (self._parent_actor.route_length - self._parent_actor.route_completed) / 1000.0 obs = { 'lateral_dist': np.array([lateral_dist], dtype=np.float32), 'angle_diff': np.array([angle_diff], dtype=np.float32), 'route_locs': np.array(location_list, dtype=np.float32), 'dist_remaining': np.array([dist_remaining_in_km], dtype=np.float32) } return obs def clean(self): self._parent_actor = None ================================================ FILE: roach/obs_manager/actor_state/speed.py ================================================ import numpy as np from gym import spaces from carla_gym.core.obs_manager.obs_manager import ObsManagerBase class ObsManager(ObsManagerBase): """ in m/s """ def __init__(self, obs_configs): self._parent_actor = None super(ObsManager, self).__init__() def _define_obs_space(self): self.obs_space = spaces.Dict({ 'speed': spaces.Box(low=-10.0, high=30.0, shape=(1,), dtype=np.float32), 'speed_xy': spaces.Box(low=-10.0, high=30.0, shape=(1,), dtype=np.float32), 'forward_speed': spaces.Box(low=-10.0, high=30.0, shape=(1,), dtype=np.float32) }) def attach_ego_vehicle(self, parent_actor): self._parent_actor = parent_actor def get_observation(self): velocity = self._parent_actor.vehicle.get_velocity() transform = self._parent_actor.vehicle.get_transform() forward_vec = transform.get_forward_vector() np_vel = np.array([velocity.x, velocity.y, velocity.z]) np_fvec = np.array([forward_vec.x, forward_vec.y, forward_vec.z]) speed = np.linalg.norm(np_vel) speed_xy = np.linalg.norm(np_vel[0:2]) forward_speed = np.dot(np_vel, np_fvec) obs = { 'speed': np.array([speed], dtype=np.float32), 'speed_xy': np.array([speed_xy], dtype=np.float32), 'forward_speed': np.array([forward_speed], dtype=np.float32) } return obs def clean(self): self._parent_actor = None ================================================ FILE: roach/obs_manager/actor_state/velocity.py ================================================ import numpy as np from gym import spaces from carla_gym.core.obs_manager.obs_manager import ObsManagerBase import carla_gym.utils.transforms as trans_utils class ObsManager(ObsManagerBase): def __init__(self, obs_configs): super(ObsManager, self).__init__() def _define_obs_space(self): # acc_x, acc_y: m/s2 # vel_x, vel_y: m/s # vel_angular z: rad/s self.obs_space = spaces.Dict({ 'acc_xy': spaces.Box(low=-1e3, high=1e3, shape=(2,), dtype=np.float32), 'vel_xy': spaces.Box(low=-1e2, high=1e2, shape=(2,), dtype=np.float32), 'vel_ang_z': spaces.Box(low=-1e3, high=1e3, shape=(1,), dtype=np.float32) }) def attach_ego_vehicle(self, parent_actor): self._parent_actor = parent_actor def get_observation(self): ev_transform = self._parent_actor.vehicle.get_transform() acc_w = self._parent_actor.vehicle.get_acceleration() vel_w = self._parent_actor.vehicle.get_velocity() ang_w = self._parent_actor.vehicle.get_angular_velocity() acc_ev = trans_utils.vec_global_to_ref(acc_w, ev_transform.rotation) vel_ev = trans_utils.vec_global_to_ref(vel_w, ev_transform.rotation) obs = { 'acc_xy': np.array([acc_ev.x, acc_ev.y], dtype=np.float32), 'vel_xy': np.array([vel_ev.x, vel_ev.y], dtype=np.float32), 'vel_ang_z': np.array([ang_w.z], dtype=np.float32) } return obs def clean(self): self._parent_actor = None ================================================ FILE: roach/obs_manager/birdview/chauffeurnet.py ================================================ import numpy as np import carla from gym import spaces import cv2 as cv from collections import deque from pathlib import Path import h5py from roach.utils.traffic_light import TrafficLightHandler COLOR_BLACK = (0, 0, 0) COLOR_RED = (255, 0, 0) COLOR_GREEN = (0, 255, 0) COLOR_BLUE = (0, 0, 255) COLOR_CYAN = (0, 255, 255) COLOR_MAGENTA = (255, 0, 255) COLOR_MAGENTA_2 = (255, 140, 255) COLOR_YELLOW = (255, 255, 0) COLOR_YELLOW_2 = (160, 160, 0) COLOR_WHITE = (255, 255, 255) COLOR_ALUMINIUM_0 = (238, 238, 236) COLOR_ALUMINIUM_3 = (136, 138, 133) COLOR_ALUMINIUM_5 = (46, 52, 54) def tint(color, factor): r, g, b = color r = int(r + (255-r) * factor) g = int(g + (255-g) * factor) b = int(b + (255-b) * factor) r = min(r, 255) g = min(g, 255) b = min(b, 255) return (r, g, b) class ObsManager(): def __init__(self, obs_configs, criteria_stop=None): self._width = int(obs_configs['width_in_pixels']) self._pixels_ev_to_bottom = obs_configs['pixels_ev_to_bottom'] self._pixels_per_meter = obs_configs['pixels_per_meter'] self._history_idx = obs_configs['history_idx'] self._scale_bbox = obs_configs.get('scale_bbox', True) self._scale_mask_col = obs_configs.get('scale_mask_col', 1.1) self._history_queue = deque(maxlen=20) self._image_channels = 3 self._masks_channels = 3 + 3*len(self._history_idx) self._parent_actor = None self._world = None self._map_dir = Path(__file__).resolve().parent / 'maps' self._criteria_stop =criteria_stop super(ObsManager, self).__init__() def attach_ego_vehicle(self, ego_vehicle): self._parent_actor = ego_vehicle self._world = self._parent_actor.get_world() maps_h5_path = self._map_dir / (self._world.get_map().name + '.h5') with h5py.File(maps_h5_path, 'r', libver='latest', swmr=True) as hf: self._road = np.array(hf['road'], dtype=np.uint8) self._lane_marking_all = np.array(hf['lane_marking_all'], dtype=np.uint8) self._lane_marking_white_broken = np.array(hf['lane_marking_white_broken'], dtype=np.uint8) self._world_offset = np.array(hf.attrs['world_offset_in_meters'], dtype=np.float32) assert np.isclose(self._pixels_per_meter, float(hf.attrs['pixels_per_meter'])) self._distance_threshold = np.ceil(self._width / self._pixels_per_meter) @staticmethod def _get_stops(criteria_stop): stop_sign = criteria_stop._target_stop_sign stops = [] if (stop_sign is not None) and (not criteria_stop._stop_completed): bb_loc = carla.Location(stop_sign.trigger_volume.location) bb_ext = carla.Vector3D(stop_sign.trigger_volume.extent) bb_ext.x = max(bb_ext.x, bb_ext.y) bb_ext.y = max(bb_ext.x, bb_ext.y) trans = stop_sign.get_transform() stops = [(carla.Transform(trans.location, trans.rotation), bb_loc, bb_ext)] return stops def get_observation(self, route_plan): ev_transform = self._parent_actor.get_transform() ev_loc = ev_transform.location ev_rot = ev_transform.rotation ev_bbox = self._parent_actor.bounding_box def is_within_distance(w): c_distance = abs(ev_loc.x - w.location.x) < self._distance_threshold \ and abs(ev_loc.y - w.location.y) < self._distance_threshold \ and abs(ev_loc.z - w.location.z) < 8.0 c_ev = abs(ev_loc.x - w.location.x) < 1.0 and abs(ev_loc.y - w.location.y) < 1.0 return c_distance and (not c_ev) vehicle_bbox_list = self._world.get_level_bbs(carla.CityObjectLabel.Vehicles) walker_bbox_list = self._world.get_level_bbs(carla.CityObjectLabel.Pedestrians) if self._scale_bbox: vehicles = self._get_surrounding_actors(vehicle_bbox_list, is_within_distance, 1.0) walkers = self._get_surrounding_actors(walker_bbox_list, is_within_distance, 2.0) else: vehicles = self._get_surrounding_actors(vehicle_bbox_list, is_within_distance) walkers = self._get_surrounding_actors(walker_bbox_list, is_within_distance) tl_green = TrafficLightHandler.get_stopline_vtx(ev_loc, 0) tl_yellow = TrafficLightHandler.get_stopline_vtx(ev_loc, 1) tl_red = TrafficLightHandler.get_stopline_vtx(ev_loc, 2) stops = self._get_stops(self._criteria_stop) self._history_queue.append((vehicles, walkers, tl_green, tl_yellow, tl_red, stops)) M_warp = self._get_warp_transform(ev_loc, ev_rot) # objects with history vehicle_masks, walker_masks, tl_green_masks, tl_yellow_masks, tl_red_masks, stop_masks \ = self._get_history_masks(M_warp) # road_mask, lane_mask road_mask = cv.warpAffine(self._road, M_warp, (self._width, self._width)).astype(np.bool) lane_mask_all = cv.warpAffine(self._lane_marking_all, M_warp, (self._width, self._width)).astype(np.bool) lane_mask_broken = cv.warpAffine(self._lane_marking_white_broken, M_warp, (self._width, self._width)).astype(np.bool) # route_mask route_mask = np.zeros([self._width, self._width], dtype=np.uint8) route_in_pixel = np.array([[self._world_to_pixel(wp.transform.location)] for wp, _ in route_plan[0:80]]) route_warped = cv.transform(route_in_pixel, M_warp) cv.polylines(route_mask, [np.round(route_warped).astype(np.int32)], False, 1, thickness=16) route_mask = route_mask.astype(np.bool) # ev_mask ev_mask = self._get_mask_from_actor_list([(ev_transform, ev_bbox.location, ev_bbox.extent)], M_warp) ev_mask_col = self._get_mask_from_actor_list([(ev_transform, ev_bbox.location, ev_bbox.extent*self._scale_mask_col)], M_warp) # render image = np.zeros([self._width, self._width, 3], dtype=np.uint8) image[road_mask] = COLOR_ALUMINIUM_5 image[route_mask] = COLOR_ALUMINIUM_3 image[lane_mask_all] = COLOR_MAGENTA image[lane_mask_broken] = COLOR_MAGENTA_2 h_len = len(self._history_idx)-1 for i, mask in enumerate(stop_masks): image[mask] = tint(COLOR_YELLOW_2, (h_len-i)*0.2) for i, mask in enumerate(tl_green_masks): image[mask] = tint(COLOR_GREEN, (h_len-i)*0.2) for i, mask in enumerate(tl_yellow_masks): image[mask] = tint(COLOR_YELLOW, (h_len-i)*0.2) for i, mask in enumerate(tl_red_masks): image[mask] = tint(COLOR_RED, (h_len-i)*0.2) for i, mask in enumerate(vehicle_masks): image[mask] = tint(COLOR_BLUE, (h_len-i)*0.2) for i, mask in enumerate(walker_masks): image[mask] = tint(COLOR_CYAN, (h_len-i)*0.2) image[ev_mask] = COLOR_WHITE # image[obstacle_mask] = COLOR_BLUE # masks c_road = road_mask * 255 c_route = route_mask * 255 c_lane = lane_mask_all * 255 c_lane[lane_mask_broken] = 120 # masks with history c_tl_history = [] for i in range(len(self._history_idx)): c_tl = np.zeros([self._width, self._width], dtype=np.uint8) c_tl[tl_green_masks[i]] = 80 c_tl[tl_yellow_masks[i]] = 170 c_tl[tl_red_masks[i]] = 255 c_tl[stop_masks[i]] = 255 c_tl_history.append(c_tl) c_vehicle_history = [m*255 for m in vehicle_masks] c_walker_history = [m*255 for m in walker_masks] masks = np.stack((c_road, c_route, c_lane, *c_vehicle_history, *c_walker_history, *c_tl_history), axis=2) masks = np.transpose(masks, [2, 0, 1]) obs_dict = {'rendered': image, 'masks': masks} # self._parent_actor.collision_px = np.any(ev_mask_col & walker_masks[-1]) return obs_dict def _get_history_masks(self, M_warp): qsize = len(self._history_queue) vehicle_masks, walker_masks, tl_green_masks, tl_yellow_masks, tl_red_masks, stop_masks = [], [], [], [], [], [] for idx in self._history_idx: idx = max(idx, -1 * qsize) vehicles, walkers, tl_green, tl_yellow, tl_red, stops = self._history_queue[idx] vehicle_masks.append(self._get_mask_from_actor_list(vehicles, M_warp)) walker_masks.append(self._get_mask_from_actor_list(walkers, M_warp)) tl_green_masks.append(self._get_mask_from_stopline_vtx(tl_green, M_warp)) tl_yellow_masks.append(self._get_mask_from_stopline_vtx(tl_yellow, M_warp)) tl_red_masks.append(self._get_mask_from_stopline_vtx(tl_red, M_warp)) stop_masks.append(self._get_mask_from_actor_list(stops, M_warp)) return vehicle_masks, walker_masks, tl_green_masks, tl_yellow_masks, tl_red_masks, stop_masks def _get_mask_from_stopline_vtx(self, stopline_vtx, M_warp): mask = np.zeros([self._width, self._width], dtype=np.uint8) for sp_locs in stopline_vtx: stopline_in_pixel = np.array([[self._world_to_pixel(x)] for x in sp_locs]) stopline_warped = cv.transform(stopline_in_pixel, M_warp) cv.line(mask, tuple(stopline_warped[0, 0].astype(np.int32)), tuple(stopline_warped[1, 0].astype(np.int32)), color=1, thickness=6) return mask.astype(np.bool) def _get_mask_from_actor_list(self, actor_list, M_warp): mask = np.zeros([self._width, self._width], dtype=np.uint8) for actor_transform, bb_loc, bb_ext in actor_list: corners = [carla.Location(x=-bb_ext.x, y=-bb_ext.y), carla.Location(x=bb_ext.x, y=-bb_ext.y), carla.Location(x=bb_ext.x, y=0), carla.Location(x=bb_ext.x, y=bb_ext.y), carla.Location(x=-bb_ext.x, y=bb_ext.y)] corners = [bb_loc + corner for corner in corners] corners = [actor_transform.transform(corner) for corner in corners] corners_in_pixel = np.array([[self._world_to_pixel(corner)] for corner in corners]) corners_warped = cv.transform(corners_in_pixel, M_warp) cv.fillConvexPoly(mask, np.round(corners_warped).astype(np.int32), 1) return mask.astype(np.bool) @staticmethod def _get_surrounding_actors(bbox_list, criterium, scale=None): actors = [] for bbox in bbox_list: is_within_distance = criterium(bbox) if is_within_distance: bb_loc = carla.Location() bb_ext = carla.Vector3D(bbox.extent) if scale is not None: bb_ext = bb_ext * scale bb_ext.x = max(bb_ext.x, 0.8) bb_ext.y = max(bb_ext.y, 0.8) actors.append((carla.Transform(bbox.location, bbox.rotation), bb_loc, bb_ext)) return actors def _get_warp_transform(self, ev_loc, ev_rot): ev_loc_in_px = self._world_to_pixel(ev_loc) yaw = np.deg2rad(ev_rot.yaw) forward_vec = np.array([np.cos(yaw), np.sin(yaw)]) right_vec = np.array([np.cos(yaw + 0.5*np.pi), np.sin(yaw + 0.5*np.pi)]) bottom_left = ev_loc_in_px - self._pixels_ev_to_bottom * forward_vec - (0.5*self._width) * right_vec top_left = ev_loc_in_px + (self._width-self._pixels_ev_to_bottom) * forward_vec - (0.5*self._width) * right_vec top_right = ev_loc_in_px + (self._width-self._pixels_ev_to_bottom) * forward_vec + (0.5*self._width) * right_vec src_pts = np.stack((bottom_left, top_left, top_right), axis=0).astype(np.float32) dst_pts = np.array([[0, self._width-1], [0, 0], [self._width-1, 0]], dtype=np.float32) return cv.getAffineTransform(src_pts, dst_pts) def _world_to_pixel(self, location, projective=False): """Converts the world coordinates to pixel coordinates""" x = self._pixels_per_meter * (location.x - self._world_offset[0]) y = self._pixels_per_meter * (location.y - self._world_offset[1]) if projective: p = np.array([x, y, 1], dtype=np.float32) else: p = np.array([x, y], dtype=np.float32) return p def _world_to_pixel_width(self, width): """Converts the world units to pixel units""" return self._pixels_per_meter * width def clean(self): self._parent_actor = None self._world = None self._history_queue.clear() ================================================ FILE: roach/obs_manager/birdview/hdmap_generate.py ================================================ import numpy as np import carla from gym import spaces import cv2 as cv from collections import deque from pathlib import Path import h5py COLOR_BLACK = (0, 0, 0) COLOR_RED = (255, 0, 0) COLOR_GREEN = (0, 255, 0) COLOR_BLUE = (0, 0, 255) COLOR_CYAN = (0, 255, 255) COLOR_MAGENTA = (255, 0, 255) COLOR_MAGENTA_2 = (255, 140, 255) COLOR_YELLOW = (255, 255, 0) COLOR_YELLOW_2 = (160, 160, 0) COLOR_WHITE = (255, 255, 255) COLOR_ALUMINIUM_0 = (238, 238, 236) COLOR_ALUMINIUM_3 = (136, 138, 133) COLOR_ALUMINIUM_5 = (46, 52, 54) def tint(color, factor): r, g, b = color r = int(r + (255-r) * factor) g = int(g + (255-g) * factor) b = int(b + (255-b) * factor) r = min(r, 255) g = min(g, 255) b = min(b, 255) return (r, g, b) ================================================ FILE: roach/rl_birdview_agent.py ================================================ import logging import numpy as np from omegaconf import OmegaConf import copy from roach.utils.config_utils import load_entry_point class RlBirdviewAgent(): def __init__(self, path_to_conf_file='config_agent.yaml', ckpt = None): self._render_dict = None self.supervision_dict = None self._ckpt = ckpt self.setup(path_to_conf_file) def setup(self, path_to_conf_file): cfg = OmegaConf.load(path_to_conf_file) cfg = OmegaConf.to_container(cfg) self._obs_configs = cfg['obs_configs'] self._train_cfg = cfg['training'] self._policy_class = load_entry_point(cfg['policy']['entry_point']) self._policy_kwargs = cfg['policy']['kwargs'] if self._ckpt is None: self._policy = None else: self._policy, self._train_cfg['kwargs'] = self._policy_class.load(self._ckpt) self._policy = self._policy.eval() self._wrapper_class = load_entry_point(cfg['env_wrapper']['entry_point']) self._wrapper_kwargs = cfg['env_wrapper']['kwargs'] def run_step(self, input_data, timestamp): input_data = copy.deepcopy(input_data) policy_input = self._wrapper_class.process_obs(input_data, self._wrapper_kwargs['input_states'], train=False) actions, values, log_probs, mu, sigma, features = self._policy.forward( policy_input, deterministic=True, clip_action=True) control = self._wrapper_class.process_act(actions, self._wrapper_kwargs['acc_as_action'], train=False) self.supervision_dict = { 'action': np.array([control.throttle, control.steer, control.brake], dtype=np.float32), 'value': values[0], 'action_mu': mu[0], 'action_sigma': sigma[0], 'features': features[0], 'speed': input_data['speed']['forward_speed'] } self.supervision_dict = copy.deepcopy(self.supervision_dict) return control @property def obs_configs(self): return self._obs_configs ================================================ FILE: roach/utils/config_utils.py ================================================ from importlib import import_module import json from pathlib import Path import socket import xml.etree.ElementTree as ET import h5py import carla import numpy as np import hydra def check_h5_maps(env_configs, obs_configs, carla_sh_path): pixels_per_meter = None for agent_id, obs_cfg in obs_configs.items(): for k,v in obs_cfg.items(): if 'birdview' in v['module']: pixels_per_meter = float(v['pixels_per_meter']) if pixels_per_meter is None: # agent does not require birdview map as observation return save_dir = Path(hydra.utils.get_original_cwd()) / 'carla_gym/core/obs_manager/birdview/maps' txt_command = f'Please run map generation script from project root directory. \n' \ f'\033[93m' \ f'python -m carla_gym.utils.birdview_map ' \ f'--save_dir {save_dir} --pixels_per_meter {pixels_per_meter:.2f} ' \ f'--carla_sh_path {carla_sh_path}' \ f'\033[0m' # check if pixels_per_meter match for env_cfg in env_configs: carla_map = env_cfg['env_configs']['carla_map'] hf_file_path = save_dir / (carla_map+'.h5') file_exists = hf_file_path.exists() if file_exists: map_hf = h5py.File(hf_file_path, 'r') hf_pixels_per_meter = float(map_hf.attrs['pixels_per_meter']) map_hf.close() pixels_per_meter_match = np.isclose(hf_pixels_per_meter, pixels_per_meter) txt_assert = f'pixel_per_meter mismatch between h5 file ({hf_pixels_per_meter}) '\ f'and obs_config ({pixels_per_meter}). ' else: txt_assert = f'{hf_file_path} does not exists. ' pixels_per_meter_match = False assert file_exists and pixels_per_meter_match, txt_assert + txt_command def load_entry_point(name): mod_name, attr_name = name.split(":") mod = import_module(mod_name) fn = getattr(mod, attr_name) return fn def load_obs_configs(agent_configs_dict): obs_configs = {} for actor_id, cfg in agent_configs_dict.items(): obs_configs[actor_id] = json.load(open(cfg['path_to_conf_file'], 'r'))['obs_configs'] return obs_configs def init_agents(agent_configs_dict, **kwargs): agents_dict = {} for actor_id, cfg in agent_configs_dict.items(): AgentClass = load_entry_point(cfg['entry_point']) agents_dict[actor_id] = AgentClass(cfg['path_to_conf_file'], **kwargs) return agents_dict def parse_routes_file(routes_xml_filename): route_descriptions_dict = {} tree = ET.parse(routes_xml_filename) for route in tree.iter("route"): route_id = int(route.attrib['id']) route_descriptions_dict[route_id] = {} for actor_type in ['ego_vehicle', 'scenario_actor']: route_descriptions_dict[route_id][actor_type+'s'] = {} for actor in route.iter(actor_type): actor_id = actor.attrib['id'] waypoint_list = [] # the list of waypoints that can be found on this route for this actor for waypoint in actor.iter('waypoint'): location = carla.Location( x=float(waypoint.attrib['x']), y=float(waypoint.attrib['y']), z=float(waypoint.attrib['z'])) rotation = carla.Rotation( roll=float(waypoint.attrib['roll']), pitch=float(waypoint.attrib['pitch']), yaw=float(waypoint.attrib['yaw'])) waypoint_list.append(carla.Transform(location, rotation)) route_descriptions_dict[route_id][actor_type+'s'][actor_id] = waypoint_list return route_descriptions_dict def get_single_route(routes_xml_filename, route_id): tree = ET.parse(routes_xml_filename) route = tree.find(f'.//route[@id="{route_id}"]') route_dict = {} for actor_type in ['ego_vehicle', 'scenario_actor']: route_dict[actor_type+'s'] = {} for actor in route.iter(actor_type): actor_id = actor.attrib['id'] waypoint_list = [] # the list of waypoints that can be found on this route for this actor for waypoint in actor.iter('waypoint'): location = carla.Location( x=float(waypoint.attrib['x']), y=float(waypoint.attrib['y']), z=float(waypoint.attrib['z'])) rotation = carla.Rotation( roll=float(waypoint.attrib['roll']), pitch=float(waypoint.attrib['pitch']), yaw=float(waypoint.attrib['yaw'])) waypoint_list.append(carla.Transform(location, rotation)) route_dict[actor_type+'s'][actor_id] = waypoint_list return route_dict def to_camel_case(snake_str, init_capital=False): # agent_class_str = to_camel_case(agent_module_str.split('.')[-1], init_capital=True) components = snake_str.split('_') if init_capital: init_letter = components[0].title() else: init_letter = components[0] return init_letter + ''.join(x.title() for x in components[1:]) def get_free_tcp_port(): s = socket.socket() s.bind(("", 0)) # Request the sys to provide a free port dynamically server_port = s.getsockname()[1] s.close() # 2000 works fine for now server_port = 2000 return server_port ================================================ FILE: roach/utils/expert_noiser.py ================================================ import time import random class ExpertNoiser(object): # define frequency into noise events per minute # define the amount_of_time of setting the noise def __init__(self, noise_type, frequency=15, intensity=10, min_noise_time_amount=2.0): # self.variable_type = variable self.noise_type = noise_type self.frequency = frequency self.noise_being_set = False self.noise_start_time = time.time() self.noise_end_time = time.time() + 1 self.min_noise_time_amount = min_noise_time_amount self.noise_time_amount = min_noise_time_amount + float(random.randint(50, 200) / 100.0) self.second_counter = time.time() self.steer_noise_time = 0 self.intensity = intensity + random.randint(-2, 2) self.remove_noise = False self.current_noise_mean = 0 def set_noise(self): if self.noise_type == 'Spike' or self.noise_type == 'Throttle': # flip between positive and negative coin = random.randint(0, 1) if coin == 0: # negative self.current_noise_mean = 0.001 # -random.gauss(0.05,0.02) else: # positive self.current_noise_mean = -0.001 # random.gauss(0.05,0.02) def get_noise(self): if self.noise_type == 'Spike' or self.noise_type == 'Throttle': if self.current_noise_mean > 0: return min(0.55, self.current_noise_mean + ( time.time() - self.noise_start_time) * 0.03 * self.intensity) else: return max(-0.55, self.current_noise_mean - ( time.time() - self.noise_start_time) * 0.03 * self.intensity) def get_noise_removing(self): # print 'REMOVING' added_noise = (self.noise_end_time - self.noise_start_time) * 0.02 * self.intensity # print added_noise if self.noise_type == 'Spike' or self.noise_type == 'Throttle': if self.current_noise_mean > 0: added_noise = min(0.55, added_noise + self.current_noise_mean) return added_noise - (time.time() - self.noise_end_time) * 0.03 * self.intensity else: added_noise = max(-0.55, self.current_noise_mean - added_noise) return added_noise + (time.time() - self.noise_end_time) * 0.03 * self.intensity def is_time_for_noise(self, steer): # Count Seconds second_passed = False if time.time() - self.second_counter >= 1.0: second_passed = True self.second_counter = time.time() if time.time() - self.noise_start_time >= self.noise_time_amount and not self.remove_noise and self.noise_being_set: self.noise_being_set = False self.remove_noise = True self.noise_end_time = time.time() if self.noise_being_set: return True if self.remove_noise: # print "TIME REMOVING ",(time.time()-self.noise_end_time) if (time.time() - self.noise_end_time) > ( self.noise_time_amount): # if half the amount put passed self.remove_noise = False self.noise_time_amount = self.min_noise_time_amount + float( random.randint(50, 200) / 100.0) return False else: return True if second_passed and not self.noise_being_set: # Ok, if noise is not being set but a second passed... we may start puting more seed = random.randint(0, 60) if seed < self.frequency: if not self.noise_being_set: self.noise_being_set = True self.set_noise() self.steer_noise_time = steer self.noise_start_time = time.time() return True else: return False else: return False def set_noise_exist(self, noise_exist): self.noise_being_set = noise_exist def compute_noise(self, action, speed): # noisy_action = action if self.noise_type == 'None': return action, False, False if self.noise_type == 'Spike': if self.is_time_for_noise(action.steer): steer = action.steer if self.remove_noise: steer_noisy = max( min(steer + self.get_noise_removing() * (25 / (2.3 * speed + 5)), 1), -1) else: steer_noisy = max(min(steer + self.get_noise() * (25 / (2.3 * speed + 5)), 1), -1) noisy_action = action noisy_action.steer = steer_noisy return noisy_action, False, not self.remove_noise else: return action, False, False if self.noise_type == 'Throttle': if self.is_time_for_noise(action.throttle): throttle_noisy = action.throttle brake_noisy = action.brake if self.remove_noise: # print(" Throttle noise removing", self.get_noise_removing()) noise = self.get_noise_removing() if noise > 0: throttle_noisy = max(min(throttle_noisy + noise, 1), 0) else: brake_noisy = max(min(brake_noisy + -noise, 1), 0) else: # print(" Throttle noise ", self.get_noise()) noise = self.get_noise() if noise > 0: throttle_noisy = max(min(throttle_noisy + noise, 1), 0) else: brake_noisy = max(min(brake_noisy + -noise, 1), 0) noisy_action = action noisy_action.throttle = throttle_noisy noisy_action.brake = brake_noisy # print 'timefornosie' return noisy_action, False, not self.remove_noise else: return action, False, False ================================================ FILE: roach/utils/rl_birdview_wrapper.py ================================================ import gym import numpy as np import cv2 import carla eval_num_zombie_vehicles = { 'Town01': 120, 'Town02': 70, 'Town03': 70, 'Town04': 150, 'Town05': 120, 'Town06': 120 } eval_num_zombie_walkers = { 'Town01': 120, 'Town02': 70, 'Town03': 70, 'Town04': 80, 'Town05': 120, 'Town06': 80 } class RlBirdviewWrapper(gym.Wrapper): def __init__(self, env, input_states=[], acc_as_action=False): assert len(env._obs_configs) == 1 self._ev_id = list(env._obs_configs.keys())[0] self._input_states = input_states self._acc_as_action = acc_as_action self._render_dict = {} state_spaces = [] if 'speed' in self._input_states: state_spaces.append(env.observation_space[self._ev_id]['speed']['speed_xy']) if 'speed_limit' in self._input_states: state_spaces.append(env.observation_space[self._ev_id]['control']['speed_limit']) if 'control' in self._input_states: state_spaces.append(env.observation_space[self._ev_id]['control']['throttle']) state_spaces.append(env.observation_space[self._ev_id]['control']['steer']) state_spaces.append(env.observation_space[self._ev_id]['control']['brake']) state_spaces.append(env.observation_space[self._ev_id]['control']['gear']) if 'acc_xy' in self._input_states: state_spaces.append(env.observation_space[self._ev_id]['velocity']['acc_xy']) if 'vel_xy' in self._input_states: state_spaces.append(env.observation_space[self._ev_id]['velocity']['vel_xy']) if 'vel_ang_z' in self._input_states: state_spaces.append(env.observation_space[self._ev_id]['velocity']['vel_ang_z']) state_low = np.concatenate([s.low for s in state_spaces]) state_high = np.concatenate([s.high for s in state_spaces]) env.observation_space = gym.spaces.Dict( {'state': gym.spaces.Box(low=state_low, high=state_high, dtype=np.float32), 'birdview': env.observation_space[self._ev_id]['birdview']['masks']}) if self._acc_as_action: # act: acc(throttle/brake), steer env.action_space = gym.spaces.Box(low=np.array([-1, -1]), high=np.array([1, 1]), dtype=np.float32) else: # act: throttle, steer, brake env.action_space = gym.spaces.Box(low=np.array([0, -1, 0]), high=np.array([1, 1, 1]), dtype=np.float32) super(RlBirdviewWrapper, self).__init__(env) self.eval_mode = False def step(self, action): action_ma = {self._ev_id: self.process_act(action, self._acc_as_action)} obs_ma, reward_ma, done_ma, info_ma = self.env.step(action_ma) obs = self.process_obs(obs_ma[self._ev_id], self._input_states) reward = reward_ma[self._ev_id] done = done_ma[self._ev_id] info = info_ma[self._ev_id] self._render_dict = { 'timestamp': self.env.timestamp, 'obs': self._render_dict['prev_obs'], 'prev_obs': obs, 'im_render': self._render_dict['prev_im_render'], 'prev_im_render': obs_ma[self._ev_id]['birdview']['rendered'], 'action': action, 'reward_debug': info['reward_debug'], 'terminal_debug': info['terminal_debug'] } return obs, reward, done, info @staticmethod def process_obs(obs, input_states, train=True): state_list = [] if 'speed' in input_states: state_list.append(obs['speed']['speed_xy']) if 'speed_limit' in input_states: state_list.append(obs['control']['speed_limit']) if 'control' in input_states: state_list.append(obs['control']['throttle']) state_list.append(obs['control']['steer']) state_list.append(obs['control']['brake']) state_list.append(obs['control']['gear']/5.0) if 'acc_xy' in input_states: state_list.append(obs['velocity']['acc_xy']) if 'vel_xy' in input_states: state_list.append(obs['velocity']['vel_xy']) if 'vel_ang_z' in input_states: state_list.append(obs['velocity']['vel_ang_z']) state = np.concatenate(state_list) birdview = obs['birdview']['masks'] if not train: birdview = np.expand_dims(birdview, 0) state = np.expand_dims(state, 0) obs_dict = { 'state': state.astype(np.float32), 'birdview': birdview } return obs_dict @staticmethod def process_act(action, acc_as_action, train=True): if not train: action = action[0] if acc_as_action: acc, steer = action.astype(np.float64) if acc >= 0.0: throttle = acc brake = 0.0 else: throttle = 0.0 brake = np.abs(acc) else: throttle, steer, brake = action.astype(np.float64) throttle = np.clip(throttle, 0, 1) steer = np.clip(steer, -1, 1) brake = np.clip(brake, 0, 1) control = carla.VehicleControl(throttle=throttle, steer=steer, brake=brake) return control ================================================ FILE: roach/utils/traffic_light.py ================================================ from collections import deque import carla import numpy as np import roach.utils.transforms as trans_utils def _get_traffic_light_waypoints(traffic_light, carla_map): """ get area of a given traffic light adapted from "carla-simulator/scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_criteria.py" """ base_transform = traffic_light.get_transform() tv_loc = traffic_light.trigger_volume.location tv_ext = traffic_light.trigger_volume.extent # Discretize the trigger box into points x_values = np.arange(-0.9 * tv_ext.x, 0.9 * tv_ext.x, 1.0) # 0.9 to avoid crossing to adjacent lanes area = [] for x in x_values: point_location = base_transform.transform(tv_loc + carla.Location(x=x)) area.append(point_location) # Get the waypoints of these points, removing duplicates ini_wps = [] for pt in area: wpx = carla_map.get_waypoint(pt) # As x_values are arranged in order, only the last one has to be checked if not ini_wps or ini_wps[-1].road_id != wpx.road_id or ini_wps[-1].lane_id != wpx.lane_id: ini_wps.append(wpx) # Leaderboard: Advance them until the intersection stopline_wps = [] stopline_vertices = [] junction_wps = [] for wpx in ini_wps: # Below: just use trigger volume, otherwise it's on the zebra lines. # stopline_wps.append(wpx) # vec_forward = wpx.transform.get_forward_vector() # vec_right = carla.Vector3D(x=-vec_forward.y, y=vec_forward.x, z=0) # loc_left = wpx.transform.location - 0.4 * wpx.lane_width * vec_right # loc_right = wpx.transform.location + 0.4 * wpx.lane_width * vec_right # stopline_vertices.append([loc_left, loc_right]) while not wpx.is_intersection: next_wp = wpx.next(0.5)[0] if next_wp and not next_wp.is_intersection: wpx = next_wp else: break junction_wps.append(wpx) stopline_wps.append(wpx) vec_forward = wpx.transform.get_forward_vector() vec_right = carla.Vector3D(x=-vec_forward.y, y=vec_forward.x, z=0) loc_left = wpx.transform.location - 0.4 * wpx.lane_width * vec_right loc_right = wpx.transform.location + 0.4 * wpx.lane_width * vec_right stopline_vertices.append([loc_left, loc_right]) # all paths at junction for this traffic light junction_paths = [] path_wps = [] wp_queue = deque(junction_wps) while len(wp_queue) > 0: current_wp = wp_queue.pop() path_wps.append(current_wp) next_wps = current_wp.next(1.0) for next_wp in next_wps: if next_wp.is_junction: wp_queue.append(next_wp) else: junction_paths.append(path_wps) path_wps = [] return carla.Location(base_transform.transform(tv_loc)), stopline_wps, stopline_vertices, junction_paths class TrafficLightHandler: num_tl = 0 list_tl_actor = [] list_tv_loc = [] list_stopline_wps = [] list_stopline_vtx = [] list_junction_paths = [] carla_map = None @staticmethod def reset(world): TrafficLightHandler.carla_map = world.get_map() TrafficLightHandler.num_tl = 0 TrafficLightHandler.list_tl_actor = [] TrafficLightHandler.list_tv_loc = [] TrafficLightHandler.list_stopline_wps = [] TrafficLightHandler.list_stopline_vtx = [] TrafficLightHandler.list_junction_paths = [] all_actors = world.get_actors() for _actor in all_actors: if 'traffic_light' in _actor.type_id: tv_loc, stopline_wps, stopline_vtx, junction_paths = _get_traffic_light_waypoints( _actor, TrafficLightHandler.carla_map) TrafficLightHandler.list_tl_actor.append(_actor) TrafficLightHandler.list_tv_loc.append(tv_loc) TrafficLightHandler.list_stopline_wps.append(stopline_wps) TrafficLightHandler.list_stopline_vtx.append(stopline_vtx) TrafficLightHandler.list_junction_paths.append(junction_paths) TrafficLightHandler.num_tl += 1 @staticmethod def get_light_state(vehicle, offset=0.0, dist_threshold=15.0): ''' vehicle: carla.Vehicle ''' vec_tra = vehicle.get_transform() veh_dir = vec_tra.get_forward_vector() hit_loc = vec_tra.transform(carla.Location(x=offset)) hit_wp = TrafficLightHandler.carla_map.get_waypoint(hit_loc) light_loc = None light_state = None light_id = None for i in range(TrafficLightHandler.num_tl): traffic_light = TrafficLightHandler.list_tl_actor[i] tv_loc = 0.5*TrafficLightHandler.list_stopline_wps[i][0].transform.location \ + 0.5*TrafficLightHandler.list_stopline_wps[i][-1].transform.location distance = np.sqrt((tv_loc.x-hit_loc.x)**2 + (tv_loc.y-hit_loc.y)**2) if distance > dist_threshold: continue for wp in TrafficLightHandler.list_stopline_wps[i]: wp_dir = wp.transform.get_forward_vector() dot_ve_wp = veh_dir.x * wp_dir.x + veh_dir.y * wp_dir.y + veh_dir.z * wp_dir.z wp_1 = wp.previous(4.0)[0] same_road = (hit_wp.road_id == wp.road_id) and (hit_wp.lane_id == wp.lane_id) same_road_1 = (hit_wp.road_id == wp_1.road_id) and (hit_wp.lane_id == wp_1.lane_id) # if (wp.road_id != wp_1.road_id) or (wp.lane_id != wp_1.lane_id): # print(f'Traffic Light Problem: {wp.road_id}={wp_1.road_id}, {wp.lane_id}={wp_1.lane_id}') if (same_road or same_road_1) and dot_ve_wp > 0: # This light is red and is affecting our lane loc_in_ev = trans_utils.loc_global_to_ref(wp.transform.location, vec_tra) light_loc = np.array([loc_in_ev.x, loc_in_ev.y, loc_in_ev.z], dtype=np.float32) light_state = traffic_light.state light_id = traffic_light.id break return light_state, light_loc, light_id @staticmethod def get_junctoin_paths(veh_loc, color=0, dist_threshold=50.0): if color == 0: tl_state = carla.TrafficLightState.Green elif color == 1: tl_state = carla.TrafficLightState.Yellow elif color == 2: tl_state = carla.TrafficLightState.Red junctoin_paths = [] for i in range(TrafficLightHandler.num_tl): traffic_light = TrafficLightHandler.list_tl_actor[i] tv_loc = TrafficLightHandler.list_tv_loc[i] if tv_loc.distance(veh_loc) > dist_threshold: continue if traffic_light.state != tl_state: continue junctoin_paths += TrafficLightHandler.list_junction_paths[i] return junctoin_paths @staticmethod def get_stopline_vtx(veh_loc, color, dist_threshold=50.0): if color == 0: tl_state = carla.TrafficLightState.Green elif color == 1: tl_state = carla.TrafficLightState.Yellow elif color == 2: tl_state = carla.TrafficLightState.Red stopline_vtx = [] for i in range(TrafficLightHandler.num_tl): traffic_light = TrafficLightHandler.list_tl_actor[i] tv_loc = TrafficLightHandler.list_tv_loc[i] if tv_loc.distance(veh_loc) > dist_threshold: continue if traffic_light.state != tl_state: continue stopline_vtx += TrafficLightHandler.list_stopline_vtx[i] return stopline_vtx ================================================ FILE: roach/utils/transforms.py ================================================ import numpy as np import carla def loc_global_to_ref(target_loc_in_global, ref_trans_in_global): """ :param target_loc_in_global: carla.Location in global coordinate (world, actor) :param ref_trans_in_global: carla.Transform in global coordinate (world, actor) :return: carla.Location in ref coordinate """ x = target_loc_in_global.x - ref_trans_in_global.location.x y = target_loc_in_global.y - ref_trans_in_global.location.y z = target_loc_in_global.z - ref_trans_in_global.location.z vec_in_global = carla.Vector3D(x=x, y=y, z=z) vec_in_ref = vec_global_to_ref(vec_in_global, ref_trans_in_global.rotation) target_loc_in_ref = carla.Location(x=vec_in_ref.x, y=vec_in_ref.y, z=vec_in_ref.z) return target_loc_in_ref def vec_global_to_ref(target_vec_in_global, ref_rot_in_global): """ :param target_vec_in_global: carla.Vector3D in global coordinate (world, actor) :param ref_rot_in_global: carla.Rotation in global coordinate (world, actor) :return: carla.Vector3D in ref coordinate """ R = carla_rot_to_mat(ref_rot_in_global) np_vec_in_global = np.array([[target_vec_in_global.x], [target_vec_in_global.y], [target_vec_in_global.z]]) np_vec_in_ref = R.T.dot(np_vec_in_global) target_vec_in_ref = carla.Vector3D(x=np_vec_in_ref[0, 0], y=np_vec_in_ref[1, 0], z=np_vec_in_ref[2, 0]) return target_vec_in_ref def rot_global_to_ref(target_rot_in_global, ref_rot_in_global): target_roll_in_ref = cast_angle(target_rot_in_global.roll - ref_rot_in_global.roll) target_pitch_in_ref = cast_angle(target_rot_in_global.pitch - ref_rot_in_global.pitch) target_yaw_in_ref = cast_angle(target_rot_in_global.yaw - ref_rot_in_global.yaw) target_rot_in_ref = carla.Rotation(roll=target_roll_in_ref, pitch=target_pitch_in_ref, yaw=target_yaw_in_ref) return target_rot_in_ref def rot_ref_to_global(target_rot_in_ref, ref_rot_in_global): target_roll_in_global = cast_angle(target_rot_in_ref.roll + ref_rot_in_global.roll) target_pitch_in_global = cast_angle(target_rot_in_ref.pitch + ref_rot_in_global.pitch) target_yaw_in_global = cast_angle(target_rot_in_ref.yaw + ref_rot_in_global.yaw) target_rot_in_global = carla.Rotation(roll=target_roll_in_global, pitch=target_pitch_in_global, yaw=target_yaw_in_global) return target_rot_in_global def carla_rot_to_mat(carla_rotation): """ Transform rpy in carla.Rotation to rotation matrix in np.array :param carla_rotation: carla.Rotation :return: np.array rotation matrix """ roll = np.deg2rad(carla_rotation.roll) pitch = np.deg2rad(carla_rotation.pitch) yaw = np.deg2rad(carla_rotation.yaw) yaw_matrix = np.array([ [np.cos(yaw), -np.sin(yaw), 0], [np.sin(yaw), np.cos(yaw), 0], [0, 0, 1] ]) pitch_matrix = np.array([ [np.cos(pitch), 0, -np.sin(pitch)], [0, 1, 0], [np.sin(pitch), 0, np.cos(pitch)] ]) roll_matrix = np.array([ [1, 0, 0], [0, np.cos(roll), np.sin(roll)], [0, -np.sin(roll), np.cos(roll)] ]) rotation_matrix = yaw_matrix.dot(pitch_matrix).dot(roll_matrix) return rotation_matrix def get_loc_rot_vel_in_ev(actor_list, ev_transform, get_acceleration = False, origin = False): location, rotation, absolute_velocity = [], [], [] if get_acceleration: absolute_acceleration = [] if origin: origin_velocity = [] origin_acceleration = [] for actor in actor_list: # location location_in_world = actor.get_transform().location location_in_ev = loc_global_to_ref(location_in_world, ev_transform) location.append([location_in_ev.x, location_in_ev.y, location_in_ev.z]) # rotation rotation_in_world = actor.get_transform().rotation rotation_in_ev = rot_global_to_ref(rotation_in_world, ev_transform.rotation) rotation.append([rotation_in_ev.roll, rotation_in_ev.pitch, rotation_in_ev.yaw]) # velocity vel_in_world = actor.get_velocity() vel_in_ev = vec_global_to_ref(vel_in_world, ev_transform.rotation) absolute_velocity.append([vel_in_ev.x, vel_in_ev.y, vel_in_ev.z]) if get_acceleration: # acceleration acc_in_world = actor.get_acceleration() acc_in_ev = vec_global_to_ref(acc_in_world, ev_transform.rotation) absolute_acceleration.append([acc_in_ev.x, acc_in_ev.y, acc_in_ev.z]) if origin: origin_velocity.append([vel_in_world.x, vel_in_world.y, vel_in_world.z]) origin_acceleration.append([acc_in_world.x, acc_in_world.y, acc_in_world.z]) if get_acceleration: if origin: return location, rotation, absolute_velocity, absolute_acceleration, origin_velocity, origin_acceleration return location, rotation, absolute_velocity, absolute_acceleration return np.array(location), np.array(rotation), np.array(absolute_velocity) def get_loc_rot_in_global(actor_list): location, rotation = [], [] for actor in actor_list: location_in_world = actor.get_transform().location location.append([location_in_world.x, location_in_world.y, location_in_world.z]) rotation_in_world = actor.get_transform().rotation rotation.append([rotation_in_world.roll, rotation_in_world.pitch, rotation_in_world.yaw]) return np.array(location), np.array(rotation) def cast_angle(x): # cast angle to [-180, +180) return (x+180.0)%360.0-180.0 ================================================ FILE: roach/utils/wandb_callback.py ================================================ import numpy as np import time from pathlib import Path import wandb from stable_baselines3.common.callbacks import BaseCallback from gym.wrappers.monitoring.video_recorder import ImageEncoder from omegaconf import OmegaConf class WandbCallback(BaseCallback): def __init__(self, cfg, vec_env): super(WandbCallback, self).__init__(verbose=1) # save_dir = Path.cwd() # self._save_dir = save_dir self._video_path = Path('video') self._video_path.mkdir(parents=True, exist_ok=True) self._ckpt_dir = Path('ckpt') self._ckpt_dir.mkdir(parents=True, exist_ok=True) # wandb.init(project=cfg.wb_project, dir=save_dir, name=cfg.wb_runname) wandb.init(project=cfg.wb_project, name=cfg.wb_name, notes=cfg.wb_notes, tags=cfg.wb_tags) wandb.config.update(OmegaConf.to_container(cfg)) wandb.save('./config_agent.yaml') wandb.save('.hydra/*') self.vec_env = vec_env self._eval_step = int(1e5) self._buffer_step = int(1e5) def _init_callback(self): self.n_epoch = 0 self._last_time_buffer = self.model.num_timesteps self._last_time_eval = self.model.num_timesteps def _on_step(self) -> bool: return True def _on_training_start(self) -> None: pass def _on_rollout_start(self): # self.model._last_obs = self.model.env.reset() pass def _on_training_end(self) -> None: print(f'n_epoch: {self.n_epoch}, num_timesteps: {self.model.num_timesteps}') # save time time_elapsed = time.time() - self.model.start_time wandb.log({ 'time/n_epoch': self.n_epoch, 'time/sec_per_epoch': time_elapsed / (self.n_epoch+1), 'time/fps': (self.model.num_timesteps-self.model.start_num_timesteps) / time_elapsed, 'time/train': self.model.t_train, 'time/train_values': self.model.t_train_values, 'time/rollout': self.model.t_rollout }, step=self.model.num_timesteps) wandb.log(self.model.train_debug, step=self.model.num_timesteps) # evaluate and save checkpoint if (self.model.num_timesteps - self._last_time_eval) >= self._eval_step: self._last_time_eval = self.model.num_timesteps # evaluate eval_video_path = (self._video_path / f'eval_{self.model.num_timesteps}.mp4').as_posix() avg_ep_stat, ep_events = self.evaluate_policy(self.vec_env, self.model.policy, eval_video_path) # log to wandb wandb.log({f'video/{self.model.num_timesteps}': wandb.Video(eval_video_path)}, step=self.model.num_timesteps) wandb.log(avg_ep_stat, step=self.model.num_timesteps) # save events # eval_json_path = (video_path / f'event_{self.model.num_timesteps}.json').as_posix() # with open(eval_json_path, 'w') as fd: # json.dump(ep_events, fd, indent=4, sort_keys=False) # wandb.save(eval_json_path) ckpt_path = (self._ckpt_dir / f'ckpt_{self.model.num_timesteps}.pth').as_posix() self.model.save(ckpt_path) wandb.save(f'./{ckpt_path}') self.n_epoch += 1 # CONFIGHACK: curriculum # num_zombies = {} # for i in range(self.vec_env.num_envs): # env_all_tasks = self.vec_env.get_attr('all_tasks',indices=i)[0] # num_zombies[f'train/n_veh/{i}'] = env_all_tasks[0]['num_zombie_vehicles'] # num_zombies[f'train/n_ped/{i}'] = env_all_tasks[0]['num_zombie_walkers'] # if wandb.config['curriculum']: # if avg_ep_stat['eval/route_completed_in_km'] > 1.0: # # and avg_ep_stat['eval/red_light']>0: # for env_task in env_all_tasks: # env_task['num_zombie_vehicles'] += 10 # env_task['num_zombie_walkers'] += 10 # self.vec_env.set_attr('all_tasks', env_all_tasks, indices=i) # wandb.log(num_zombies, step=self.model.num_timesteps) def _on_rollout_end(self): wandb.log({'time/rollout': self.model.t_rollout}, step=self.model.num_timesteps) # save rollout statistics avg_ep_stat = self.get_avg_ep_stat(self.model.ep_stat_buffer, prefix='rollout/') wandb.log(avg_ep_stat, step=self.model.num_timesteps) # action, mu, sigma histogram action_statistics = np.array(self.model.action_statistics) mu_statistics = np.array(self.model.mu_statistics) sigma_statistics = np.array(self.model.sigma_statistics) n_action = action_statistics.shape[-1] action_statistics = action_statistics.reshape(-1, n_action) mu_statistics = mu_statistics.reshape(-1, n_action) sigma_statistics = sigma_statistics.reshape(-1, n_action) for i in range(n_action): # path_str = (self._save_dir/f'action{i}.csv').as_posix() # np.savetxt(path_str, action_statistics[:, i], delimiter=',') # wandb.save(path_str) wandb.log({f'action[{i}]': wandb.Histogram(action_statistics[:, i])}, step=self.model.num_timesteps) wandb.log({f'alpha[{i}]': wandb.Histogram(mu_statistics[:, i])}, step=self.model.num_timesteps) wandb.log({f'beta[{i}]': wandb.Histogram(sigma_statistics[:, i])}, step=self.model.num_timesteps) # render buffer if (self.model.num_timesteps - self._last_time_buffer) >= self._buffer_step: self._last_time_buffer = self.model.num_timesteps buffer_video_path = (self._video_path / f'buffer_{self.model.num_timesteps}.mp4').as_posix() list_buffer_im = self.model.buffer.render() encoder = ImageEncoder(buffer_video_path, list_buffer_im[0].shape, 30, 30) for im in list_buffer_im: encoder.capture_frame(im) encoder.close() encoder = None wandb.log({f'buffer/{self.model.num_timesteps}': wandb.Video(buffer_video_path)}, step=self.model.num_timesteps) @staticmethod def evaluate_policy(env, policy, video_path, min_eval_steps=3000): policy = policy.eval() t0 = time.time() for i in range(env.num_envs): env.set_attr('eval_mode', True, indices=i) obs = env.reset() list_render = [] ep_stat_buffer = [] ep_events = {} for i in range(env.num_envs): ep_events[f'venv_{i}'] = [] n_step = 0 n_timeout = 0 env_done = np.array([False]*env.num_envs) # while n_step < min_eval_steps: while n_step < min_eval_steps or not np.all(env_done): actions, values, log_probs, mu, sigma, _ = policy.forward(obs, deterministic=True, clip_action=True) obs, reward, done, info = env.step(actions) for i in range(env.num_envs): env.set_attr('action_value', values[i], indices=i) env.set_attr('action_log_probs', log_probs[i], indices=i) env.set_attr('action_mu', mu[i], indices=i) env.set_attr('action_sigma', sigma[i], indices=i) list_render.append(env.render(mode='rgb_array')) n_step += 1 env_done |= done for i in np.where(done)[0]: ep_stat_buffer.append(info[i]['episode_stat']) ep_events[f'venv_{i}'].append(info[i]['episode_event']) n_timeout += int(info[i]['timeout']) # conda install x264=='1!152.20180717' ffmpeg=4.0.2 -c conda-forge encoder = ImageEncoder(video_path, list_render[0].shape, 30, 30) for im in list_render: encoder.capture_frame(im) encoder.close() avg_ep_stat = WandbCallback.get_avg_ep_stat(ep_stat_buffer, prefix='eval/') avg_ep_stat['eval/eval_timeout'] = n_timeout duration = time.time() - t0 avg_ep_stat['time/t_eval'] = duration avg_ep_stat['time/fps_eval'] = n_step * env.num_envs / duration for i in range(env.num_envs): env.set_attr('eval_mode', False, indices=i) obs = env.reset() return avg_ep_stat, ep_events @staticmethod def get_avg_ep_stat(ep_stat_buffer, prefix=''): avg_ep_stat = {} if len(ep_stat_buffer) > 0: for ep_info in ep_stat_buffer: for k, v in ep_info.items(): k_avg = f'{prefix}{k}' if k_avg in avg_ep_stat: avg_ep_stat[k_avg] += v else: avg_ep_stat[k_avg] = v n_episodes = float(len(ep_stat_buffer)) for k in avg_ep_stat.keys(): avg_ep_stat[k] /= n_episodes avg_ep_stat[f'{prefix}n_episodes'] = n_episodes return avg_ep_stat ================================================ FILE: scenario_runner/CARLA_VER ================================================ HOST = https://carla-releases.s3.eu-west-3.amazonaws.com/Linux RELEASE=CARLA_0.9.9 ================================================ FILE: scenario_runner/Dockerfile ================================================ from ubuntu:18.04 # Install base libs run apt-get update && apt-get install --no-install-recommends -y libpng16-16=1.6.34-1ubuntu0.18.04.2 \ libtiff5=4.0.9-5ubuntu0.3 libjpeg8=8c-2ubuntu8 build-essential=12.4ubuntu1 wget=1.19.4-1ubuntu2.2 git=1:2.17.1-1ubuntu0.7 \ python3.6=3.6.9-1~18.04ubuntu1 python3.6-dev=3.6.9-1~18.04ubuntu1 python3-pip=9.0.1-2.3~ubuntu1.18.04.1 \ && rm -rf /var/lib/apt/lists/* # Install python requirements run pip3 install --user setuptools==46.3.0 wheel==0.34.2 && pip3 install py_trees==0.8.3 networkx==2.2 pygame==1.9.6 \ six==1.14.0 numpy==1.18.4 psutil==5.7.0 shapely==1.7.0 xmlschema==1.1.3 ephem==3.7.6.0 tabulate==0.8.7\ && mkdir -p /app/scenario_runner # Install scenario_runner copy . /app/scenario_runner # setup environment : # # CARLA_HOST : uri for carla package without trailing slash. # For example, "https://carla-releases.s3.eu-west-3.amazonaws.com/Linux". # If this environment is not passed to docker build, the value # is taken from CARLA_VER file inside the repository. # # CARLA_RELEASE : Name of the package to be used. For example, "CARLA_0.9.9". # If this environment is not passed to docker build, the value # is taken from CARLA_VER file inside the repository. # # # It's expected that $(CARLA_HOST)/$(CARLA_RELEASE).tar.gz is a downloadable resource. # env CARLA_HOST "" env CARLA_RELEASE "" # Extract and install python API and resources from CARLA run export DEFAULT_CARLA_HOST="$(sed -e 's/^\s*HOST\s*=\s*//;t;d' /app/scenario_runner/CARLA_VER)" && \ echo "$DEFAULT_CARLA_HOST" && \ export CARLA_HOST="${CARLA_HOST:-$DEFAULT_CARLA_HOST}" && \ export DEFAULT_CARLA_RELEASE="$(sed -e 's/^\s*RELEASE\s*=\s*//;t;d' /app/scenario_runner/CARLA_VER)" && \ export CARLA_RELEASE="${CARLA_RELEASE:-$DEFAULT_CARLA_RELEASE}" && \ echo "$CARLA_HOST/$CARLA_RELEASE.tar.gz" && \ wget -qO- "$CARLA_HOST/$CARLA_RELEASE.tar.gz" | tar -xzv PythonAPI/carla -C / && \ mv /PythonAPI/carla /app/ && \ python3 -m easy_install --no-find-links --no-deps "$(find /app/carla/ -iname '*py3.*.egg' )" # Setup working environment workdir /app/scenario_runner env PYTHONPATH "${PYTHONPATH}:/app/carla/agents:/app/carla" entrypoint ["/bin/sh" ] ================================================ FILE: scenario_runner/Docs/CHANGELOG.md ================================================ ## Table of Contents * [Latest Changes](#latest-changes) * [CARLA ScenarioRunner 0.9.10](#carla-scenariorunner-0910) * [CARLA ScenarioRunner 0.9.9](#carla-scenariorunner-099) * [CARLA ScenarioRunner 0.9.8](#carla-scenariorunner-098) * [CARLA ScenarioRunner 0.9.7](#carla-scenariorunner-097) * [CARLA ScenarioRunner 0.9.6](#carla-scenariorunner-096) * [CARLA ScenarioRunner 0.9.5.1](#carla-scenariorunner-0951) * [CARLA ScenarioRunner 0.9.5](#carla-scenariorunner-095) * [CARLA ScenarioRunner 0.9.2](#carla-scenariorunner-092) ## Latest Changes ## CARLA ScenarioRunner 0.9.10 ### :rocket: New Features * Renamed some agent labels inside Jenkins CI pipelines for new standard proposals. * Added support for Jenkins CI pipelines doing automated testing and docker images creation. * **Very important:** CarlaActorPool has been removed and all its functions moved to the CarlaDataProvider: - The spawning functions have been refactored. All the *setup* functions have been removed, and its functionalities moved to their *request* counterparts. For example, previously *request_new_actor* just called *setup_actor*, but now *setup_actor* no longer exists, and the spawning is done via *request_new_actor*. They have also been unified and are now more consistent. - Changed *ActorConfiguration* to *ActorConfigurationData.parse_from_node* - Renamed the _map_ element at routes to _town_, matching the scenario configuration files * Added new environment variables needed. They can be seen at (Docs/getting_scenariorunner.md). * Improved the visual display of the information from the *output* and *file* arguments. * Routes are now deterministic in regards to the spawning scenarios when more than one are at the same location * The BackgroundActivity functionality has been unchanged but some tweaks have been made, fixing a previous patch. As a result, the *amount* parameter at *ActorConfigurationData* has been removed. * Remade how ScenarioRunner reads the scenarios files. It now reads all scenarios inside the *srunner/scenarios* folder without needing to import them. Scenarios outside that folder will still need the *--additionalScenario* argument. * The new weather parameters (related to fog) are now correctly read when running scenarios outside routes. * Enable weather animation during scenario execution (requires ephem pip package) * Changed manual control to be in par with the CARLA version. Among others, added vehicle lights, recording and some new sensors * Removed unsupported scenarios (ChallengeBasic and BackgroundActivity, VehicleTurnLeftAtJunction) * Added a new metrics module, which gives access to all the information about a scenario in order to allow the user to extract any desired information about the simulation. More information [here](metrics_module.md) * Removed the default randomness at the ControlLoss scenario * OpenSCENARIO support: - Added support for controllers and provided default implementations for vehicles and pedestrians. This required changing the handling of actors, which results in that now all actors are controlled by an OSC controller. Supported controllers: - Pedestrian controller - NPC vehicle controller (based on CARLA LocalPlanner) - Simple vehicle controller to set velocities not brake/throttle, and consider obstacles in the forward-facing region. - External controller (to forward control to external entities) - Added initial speed support for pedestrians for OpenSCENARIO - Support for EnvironmentActions within Story (before only within Init). This allows changing weather conditions during scenario execution - Added support for RelativeSpeedCondition - Added support for AccelerationCondition - Added support for TimeOfDayCondition - Added support for OffroadCondition - Added support for CollisionCondition - Added support for EndOfRoadCondition - Added support for TimeHeadwayCondition - Added support for TrafficSignalCondition - Added support for AcquirePositionAction - Extended FollowLeadingVehicle example to illustrate weather changes - Created example scenarios to illustrate usage of controllers and weather changes - Reworked the handling of Catalogs to make it compliant to the 1.0 version (relative paths have to be relative to the scenario file) - The RoadNetwork can be defined as global Parameter - Fixed handling of relative positions with negative offset - Added support for local ParamaterDeclarations - Added support for Parameters within Catalogs - Added support for ParameterAssignments for CatalogReferences - Fixed name handling of Parameters: Parameter declerations must not start with a leading '$', but when the parameter is used a leading '$' is required. - Fixed use of Parameters for multiple instances of the same Catalog element - Fixed use of relative initial positions for any actor - Added possibility to use synchronous execution mode with OpenSCENARIO - Fixed use of relative paths in CustomCommandAction - Fixed use of ControllerCatalogs * Atomics: - Several new atomics to enable usage of OSC controllers - WeatherBehavior to simulate weather over time - UpdateWeather to update weather to a new setting, e.g. sun to rain - UpdateRoadFriction to update the road friction while running - new RelativeVelocityToOtherActor trigger condition, used to compare velocities of two actors - new TriggerAcceleration trigger condition which compares a reference acceleration with the actor's one. - new TimeOfDayComparison trigger condition, comparing the simulation time (set up by the new weather system) with a given *datetime*. - Added new *OffRoadTest* criteria. - Added new *EndofRoadTest* criteria, to detect when a vehicle changes between OpenDRIVE roads. - CollisionTest criterion can now filter the collisions for a specific actor, or actor type_id. - Added a *duration* argument to *OnSidewalkTest* criteria, which makes the criteria fail after a certain time has passed, instead of doing so immediately. The default behavior has been unchanged. - InTimeToArrivalToVehicle has had its two actor arguments swapped, to match all the other behaviors. - Added *along_route* flag to InTimeToArrivalToVehicle, to take into account the topology of the road - Changed the inputs to TrafficLightStateSetter to match the other atomics, but the functionality remains unchanged ### :bug: Bug Fixes * Fixed bug causing parsing RelativeTargetSpeed tag to fail. * Fixed missing 'six' in requirements.txt * Support OpenSCENARIO parameters also if they're only part of a string value * Support Routes in Catalogs * Fix parsing of properties within ControllerCatalogs * Add cleanup of instantiated OpenSCENARIO controllers * Do not register SIGHUP signal in windows * Fixed initial speed of vehicles using OpenSCENARIO * Fixed bug causing an exception when calling BasicScenario's *_initialize_actors* with no other_actors. * Fixed bug causing the route to be downsampled (introduced by mistake at 0.9.9) * Fixed bug causing _output_ argument to not display the correct number with _InRouteTest_ and _RouteCompletionTest_ criterias (the succces and failure was correctly displayed) * Fixed bug causing OpenSCENARIO's SpeedCondition to not work as intended * Fixed bug causing CollisionConditions not to work properly in OpenSCENARIO * Fixed bug causing the *group:* functionality to behave incorrectly when moving scenarios around. * Fixed bug causing FollowLeadingVehicle and FollowLeadingVehicleWithObstacle scenarios to not properly end * Fixed bug causing CollisionTest to ignore multiple collisions with scene objects * Fixed bug causing NoSignalJunctionCrossing to not output the results of the scenario * Fixed bug causing SyncArrival to fail when the actor was destroyed after the behavior ended * Fixed bug with ending roads near stop signals to break the simulation * Fixed exception bug in spawn function of CarlaDataProvider * Fixed access to private member of CARLA LocalPlanner inside OSC NpcVehicleControl * Fixed handling of OSC LanePosition (#625) * Fixed bug causing the route repetitions to spawn different background activity * Fixed bug causing the rotate_point function inside RunningRedLightTest to not function properly. ### :ghost: Maintenance * Exposed traffic manager port flag to enable the execution of multiple scenarios on a single machine. ## CARLA ScenarioRunner 0.9.9 ### :rocket: New Features * OpenSCENARIO support: - Support for OpenSCENARIO 1.0 (a converter for old scenarios is available) - Added support for position with Lane information (roadId and laneId) - Added support to use a non-CARLA OpenDRIVE map (instead of CARLA towns) - Added support for TimeOfDay tag - Added support for scenarios with no actors * Scenario updates: - Scenarios that are part of RouteScenario have had their triggering condition modified. This will only activate when a certain parameter is set, and if not, the old trigger condition will still be applied. * Atomics: - ChangeAutopilot now calls a TM instance, and allows to change its parameters - Added WaitUntilInFront behavior and InTimeToArrivalToVehicleSideLane trigger condition, useful for cut ins - Added new trigger condition, AtRightestLane, which checks if the actor is at the rightmost driving lane - Added new criteria, ActorSpeedAboveThresholdTest, useful to check if the ego vehicle has been standing still for long periods of time. * Setting up actors in batch now also randomizes their colors * When running routes, the weather parameters of each route can now be changed at will. Check the first route at srunner/data/routes_training.xml to see the correct format to do so. By default the weather is now a sunny midday. * **Important** All challenge related content has been removed. This functionality has been improved and is now part of the [Leaderboard](https://github.com/carla-simulator/leaderboard). As a consequence: - The path to the autoagents has changed from .../challenge/autoagents to .../autoagents - The path to the route and scenario descriptions has changed from .../challenge to .../data ### :bug: Bug Fixes * Fixed spawning bugs for scenario DynamicObjectCrossing when it is part of a route * Fixed spawning bugs for scenarios VehicleTurningRight, VehicleTurningLeft when they are part of a route * Fixed bug causing the GPS coordinates given to the agents to be wrongly calculated * Fixed bug when setting up actors in batch causing to ignore the spawn points given. * Fixed bug where CollisionTest was counting as multiple hits collisions that displaced the actor for a long distance. * Fixed bug causing the simulation to end after running in synchronous mode * Fixed bug when using the WaypointFollower atomic to create new LocalPlanners for on-the-fly created actors (#502) * Fixed bug causing the scenarios to run faster than real time. ### :ghost: Maintenance * Removed perform_carla_tick() function at CarlaDataProvider, which was a workaround for world.tick() ## CARLA ScenarioRunner 0.9.8 ### :rocket: New Features * Added "--timeout" command line parameter to set a user-defined timeout value * Scenario updates: - Changed traffic light behavior of scenarios 7, 8 and 9. The new sequence is meant to greatly improve the chances of the ego vehicle having to interact at junctions. * OpenSCENARIO support: - Added initial support for Catalogs (Vehicle, Pedestrian, Environment, Maneuver, and and MiscObject types only) ### :bug: Bug Fixes * Fixed #471: Handling of weather parameter (cloudyness -> cloudiness adaption) * Fixed #472: Spawning issue of pedestrians in OpenSCENARIO * Fixed #374: Usage of evaluation critieria with multiple ego vehicles in OpenSCENARIO * Fixed #459: Add initial support for Catalogs (Vehicle, Pedestrian, Environment, Maneuver, and and MiscObject types only) * Fixed wrong StandStill behavior which return SUCCESS immediatly on a standing actor * Fixed scenario bug causing junction related scenarios (4, 7, 8 and 9) to not spawn due to lane changes. ### :ghost: Maintenance * Added watchdog to ScenarioManager to handle timeouts and CARLA crashes * Added timeout for CARLA tick() calls to avoid blocking CARLA server calls ## CARLA ScenarioRunner 0.9.7 **This is the _first_ release to work with CARLA 0.9.7 (not the patch versions 0.9.7.x)** ### :rocket: New Features * Challenge routes can be directly executed with the ScenarioRunner using the --route option * Agents can be used with the ScenarioRunner (currently only for route-based scenarios) * New scenarios: - Added example scenario for lane change - Added cut-in example scenario * Scenario updates: - Scenarios 7 to 10 are now visible when running routes (instead of being triggered in the background). Their methodology has remained unchanged * Scenario atomics: - Added new OutsideRouteLanesTest atomic criter that encompasses both SidewalkTest and WrongLaneTest, returning the percentage of route that has been traveled outside the lane. - InRouteTest is now more forgiving. The max distance has been increased, but staying above the previous one will eventually also cause failure - Changed SidewalkTest atomic criteria to also track other type of out of lane conditions - SidewalkTest and WrongLaneTest atomic criterias now track the amount of meters traversed - CollisionTest atomic criteria now correctly ignores multiple micro-collisions with the same object - Added LaneChange and TrafficLightSateSetter behavior atomics - Added AccelerateToCatchUp behavior atomic - Added get_transform() method for CarlaDataProvider - Added support for weather conditions - Added basic version check to ensure usage of correct CARLA version - WaypointFollower atomic can handle pedestrians - Extensions in WaypointFollower atomic for consecutive WaypointFollowers (one WF cancels the previous one) * Extended OpenScenario support: - Added support for UserDefinedActions (e.g. to run additional scripts) - Added init speed behavior for vehicles - Added support for relative velocities - Extended convert_position_to_transform with RelativeWorld, RelativeObject and RelativeLane osc_positions - Added new trigger atomics InTriggerDistanceToOSCPosition and InTimeToArrivalToOSCPosition to support relative osc_positions - Added new atomic behaviour ActorTransformSetterToOSCPosition - Workaround for relative osc_positions: World is started earlier to support relative osc_positions in story init - Added delay condition support in convert_condition_to_atomic - Added support for pedestrians - Full support for SimulationTime condition - Added weather support - Updated implementation to be closer to upcoming OpenSCENARIO standard - AfterTermination, AtStart conditions are supported - Added initial support for lateral action: LaneChange - Added initial support for OSCGlobalAction to set state of traffic signal - FollowRoute action is supported for vehicles and pedestrians, for global world positions. - Added support for RoadCondition: Friction - Redundant rolename object property is no longer required - Added support for global parameters - Fixed coordinate system to use right-hand as default. Left-hand CARLA system can be used by adding "CARLA:" at the start of the description in the FileHeader. - Added support to change actor color - Added support for a default actor model, in case the stated model is not available - Added support for MiscObjects (besides vehicles and pedestrians) - Reworked traffic signal handling: The name has to start now either with "id=" or "pos=" depending on whether the position or id is used as unique identifier - Actor physics can now be set via Object Properties () ### :bug: Bug Fixes * Fixed wrong handling of OpenSCENARIO ConditionGroups, which should be handled as parallel composites, not sequences * Fixed #443: Repetitions in OpenSCENARIO were not properly working * Fixed bug causing RunningStopTest atomic criteria to trigger when lane changing near a STOP signal * Fixed bug causing RunningRedLightTest atomic criteria to occasionally not trigger * Fixed bug causing occasional frame_errors * Fixed #426: Avoid underground vehicles fall forever by disabling physics when spawning underground. * Fixed #427: Removed unnecessary warnings when using get_next_traffic_light() with non-cached locations * Fixed missing ego_vehicle: compare actor IDs instead of object in CarlaDataProvider in get_velocity, get_transform and get_location * Avoided use of 'controller.ai.walker' as walker type in DynamicObjectCrossing scenario * Fixed WaypointFollower behavior to use m/s instead of km/h * Fixed starting position of VehicleTurnLeft/Right scenarios * Fixed spawn_point modification inside CarlaActorPool.setup_actor() * Fixed result of DrivenDistanceTest * Fixed exception in manual_control on fps visualization * Cleanup of pylint errors for all autonomous agents * Fixed randomness of route-based scenarios * Fixed usage of radians instead of degrees for OpenSCENARIO * Fixed ActorTransformSetter behavior to avoid vehicles not reaching the desired transform * Fixed spawning of debris for ControlLoss scenario (Scenario01) * Fixed CTRL+C termination of ScenarioRunner ### :ghost: Maintenance * Increased speed of actor initialization by using CARLA batch mode and buffering CARLA blueprint library * Split of behaviors into behaviors and conditions * Moved atomics into new submodule scenarioatomics * Updated documentation for all behaviors, conditions and test criteria * Refactoring of scenario configurations and parsers * Extended WaypointFollower atomic behavior to be able to use the current actor speed * Removed usage of 'import *' to have cleaner Python imports * Removed broad-except and bare-except where possible * Python-Scenarios: Removed obsolete categories * ScenarioRunner: Removed scenario dictonary, use imports directly * CarlaDataProvider: Simplified update_light_states() to remove code duplication * Timer: class TimeOut() is derived from SimulationTimeCondition() to avoid code duplication * Moved backported py_trees classes and methods to tools/py_trees_port.py to avoid code duplication * Removed setup_environment.sh * Adaptions to CARLA API Changes - Renamed GnssEvent to GnssMeasurement ## CARLA ScenarioRunner 0.9.6 **This is the _first_ release to work with CARLA 0.9.6** ### :ghost: Maintenance * Adapted to CARLA API changes - Frame rate is set now via Python - Renamed frame_count and frame_number to frame - Removed wait_for_tick() calls ## CARLA ScenarioRunner 0.9.5.1 **This is the _last_ release that works with CARLA 0.9.5** ### :rocket: New Features * Added initial support for OpenScenario v0.9.1 * Added support for multiple ego vehicles plus an example * Added commandline option for output directory * Added option to load external scenario implementations (in python) * Added option to scenario_runner to load external scenario XMLs * Atomic behaviors: - Extended KeepVelocity atomic behavior to support duration/distance based termination - Extended StandStill atomic behavior to support duration based termination - Added behavior to activate/deactivate autopilot ### :bug: Bug Fixes * Fixed WaypointFollower initialization ## CARLA ScenarioRunner 0.9.5 **This is the _first_ release to work with CARLA 0.9.5** ### :rocket: New Features * Added support for CARLA challenge - Added logging functionalities to challenge_evaluator_routes.py - Added wall clock timeout for the CARLA challenge - Added background scenario to generate dynamic traffic using autopilot - Updated compatibility with Python 2.7 for the challenge evaluator - Updated WaypointFollower behavior - Added detect_lane_obstacle() helper function which identifies if an obstacle is present in front of the reference actor - Added test to detect vehicles running a stop - Updated the reference position for a scenario is now called trigger_point - Added universal access to the map without re-calling get_map() - Added criteria_enable flag to enable/disable criteria tree - Added multiple helper methods for generic scenario execution. - Added pseudo-sensors for SceneLayoutMeasurements and ObjectMeasurements for Track4 of the CARLA AD challenge - Added track identification for autonomous_agent.py - Added HDMap pseudo-sensor - Added new traffic event logger - Added various helper methods to allow generic scenario execution - Added method to calculate distance along a route - In challenge mode spawn exception are caught and the corresponding scenario is removed * Added new atomic behaviors using py_trees behavior tree library - BasicAgentBehavior: drive to target location using CARLA's BasicAgent - StandStill: check if a vehicle stands still - InTriggerDistanceToNextIntersection: check if a vehicle is within certain distance with respect to the next intersection - WaypointFollower: follows auto-generated waypoints indefinitely or follows a given waypoint list - HandBrakeVehicle: sets the handbrake value for a given actor - ActorDestroy: destroys a given actor - ActorTransformSetter: sets transform of given actor - ActorSource: creates actors indefinitely around a location if no other vehicles are present within a threshold - ActorSink: indefinitely destroys vehicles that wander close to a location within a threshold - InTriggerDistanceToLocationAlongRoute: check if an actor is within a certain distance to a given location along a given route * Added new atomic evaluation criteria - Added running red light test - Added running stop test - Added wrong way test * Added NHTSA Traffic Scenarios - Updated all traffic scenarios to let the other actors appear upon scenario triggering and removal on scenario end - ManeuverOppositeDirection: hero vehicle must maneuver in the opposite lane to pass a leading vehicle. - OtherLeadingVehicle: hero vehicle must react to the deceleration of leading vehicle and change lane to avoid collision and follow the vehicle in changed lane - SignalizedJunctionRightTurn: hero vehicle must turn right into the same direction of another vehicle crossing straight initially from a lateral direction and avoid collision at a signalized intersection. - SignalizedJunctionLeftTurn : hero vehicle is turning left at signalized intersection, cuts across the path of another vehicle coming straight crossing from an opposite direction. ### :bug: Bug Fixes * Fixed SteerVehicle atomic behavior to keep vehicle velocity ### :ghost: Maintenance * Reworked scenario execution - Updated folder structure and naming convention in lowercase - Extended CarlaDataProvider with method to get next relevant traffic light - Every scenario has to have a configuration provided as XML file. Currently there is one XML file for each scenario class - The scenario runner is now responsible for spawning/destroying the ego vehicle - Added a CarlaActorPool to share scenario-related actors between scenarios and the scenario_runner - Renamed vehicle -> actor - If all scenarios in one configurations file should be executed, the scenario_runner can be started with --scenario group: - Generalized ControlLoss and FollowLeadingVehicle scenarios - Added randomization option to scenario_runner and scenarios - The scenario behavior always starts with a wait behavior until the ego vehicle reached the scenario starting position - Created method _initialize_actors in basic scenario that can be overridden for scenario specific actor initialization * Updated NHTSA Traffic Scenarios - OppositeVehicleRunningRedLight: Updated to allow execution at different locations ## CARLA ScenarioRunner 0.9.2 **This release is designed to work with CARLA 0.9.2** ### :rocket: New Features * Added Traffic Scenarios engine to reproduce complex traffic situations for training and evaluating driving agents * Added NHTSA Traffic Scenarios - FollowLeadingVehicle: hero vehicle must react to the deceleration of a leading vehicle - FollowLeadingVehicleWithObstacle: hero vehicle must react to a leading vehicle due to an obstacle blocking the road - StationaryObjectCrossing: hero vehicle must react to a cyclist or pedestrian blocking the road - DynamicObjectCrossing: hero vehicle must react to a cyclist or pedestrian suddenly crossing in front of it - OppositeVehicleRunningRedLight: hero vehicle must avoid a collision at an intersection regulated by traffic lights when the crossing traffic runs a red light - NoSignalJunctionCrossing: hero vehicle must cross a non-signalized intersection - VehicleTurningRight: hero vehicle must react to a cyclist or pedestrian crossing ahead after a right turn - VehicleTurningLeft: hero vehicle must react to a cyclist or pedestrian crossing ahead after a left turn - ControlLoss: Hero vehicle must react to a control loss and regain its control * Added atomic behaviors using py_trees behavior trees library - InTriggerRegion: new behavior to check if an object is within a trigger region - InTriggerDistanceToVehicle: check if a vehicle is within certain distance with respect to a reference vehicle - InTriggerDistanceToLocation: check if a vehicle is within certain distance with respect to a reference location - TriggerVelocity: triggers if a velocity is met - InTimeToArrivalToLocation: check if a vehicle arrives within a given time budget to a reference location - InTimeToArrivalToVehicle: check if a vehicle arrives within a given time budget to a reference vehicle - AccelerateToVelocity: accelerate until reaching requested velocity - KeepVelocity: keep constant velocity - DriveDistance: drive certain distance - UseAutoPilot: enable autopilot - StopVehicle: stop vehicle - WaitForTrafficLightState: wait for the traffic light to have a given state - SyncArrival: sync the arrival of two vehicles to a given target - AddNoiseToVehicle: Add noise to steer as well as throttle of the vehicle ================================================ FILE: scenario_runner/Docs/CODE_OF_CONDUCT.md ================================================ # Contributor Covenant Code of Conduct ## Our Pledge In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, education, socio-economic status, nationality, personal appearance, race, religion, or sexual identity and orientation. ## Our Standards Examples of behavior that contributes to creating a positive environment include: * Using welcoming and inclusive language * Being respectful of differing viewpoints and experiences * Gracefully accepting constructive criticism * Focusing on what is best for the community * Showing empathy towards other community members Examples of unacceptable behavior by participants include: * The use of sexualized language or imagery and unwelcome sexual attention or advances * Trolling, insulting/derogatory comments, and personal or political attacks * Public or private harassment * Publishing others' private information, such as a physical or electronic address, without explicit permission * Other conduct which could reasonably be considered inappropriate in a professional setting ## Our Responsibilities Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior. Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful. ## Scope This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers. ## Enforcement Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at [INSERT EMAIL ADDRESS]. All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately. Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership. ## Attribution This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html [homepage]: https://www.contributor-covenant.org ================================================ FILE: scenario_runner/Docs/CONTRIBUTING.md ================================================ Contributing to CARLA ===================== We are more than happy to accept contributions! How can I contribute? * Reporting bugs * Feature requests * Improving documentation * Code contributions Reporting bugs -------------- Use our [issue section][issueslink] on GitHub. Please check before that the issue is not already reported, and make sure you have read our CARLA [Documentation][docslink] and [FAQ][faqlink]. [issueslink]: https://github.com/carla-simulator/scenario_runner/issues [docslink]: http://carla.readthedocs.io [faqlink]: http://carla.readthedocs.io/en/latest/faq/ Feature requests ---------------- Please check first the list of [feature requests][frlink]. If it is not there and you think is a feature that might be interesting for users, please submit your request as a new issue. [frlink]: https://github.com/carla-simulator/scenario_runner/issues?q=is%3Aissue+is%3Aopen+label%3A%22feature+request%22+sort%3Acomments-desc Improving documentation ----------------------- If you feel something is missing in the documentation, please don't hesitate to open an issue to let us know. Even better, if you think you can improve it yourself, it would be a great contribution to the community! We build our documentation with [MkDocs](http://www.mkdocs.org/) based on the Markdown files inside the "Docs" folder. You can either directly modify them on GitHub or locally in your machine. Once you are done with your changes, please submit a pull-request. **TIP:** You can build and serve it locally by running `mkdocs` in the project's main folder $ sudo pip install mkdocs $ mkdocs serve Code contributions ------------------ So you are considering making a code contribution, great! we love to have contributions from the community. Before starting hands-on on coding, please check out our [issue board][wafflelink] to see if we are already working on that, it would be a pity putting an effort into something just to discover that someone else was already working on that. In case of doubt or to discuss how to proceed, please contact one of us (or send an email to carla.simulator@gmail.com). [wafflelink]: https://waffle.io/carla-simulator/scenario_runner #### What should I know before I get started? Check out the ["CARLA Documentation"][docslink] to get an idea on CARLA. In addition you may want to check the [Getting started](getting_started.md) document. [docslink]: http://carla.readthedocs.io #### Coding standard Please follow the current [coding standard](coding_standard.md) when submitting new code. #### Pull-requests Once you think your contribution is ready to be added to CARLA, please submit a pull-request. Try to be as descriptive as possible when filling the pull-request description. Adding images and gifs may help people to understand your changes or new features. Please note that there are some checks that the new code is required to pass before we can do the merge. The checks are automatically run by the continuous integration system, you will see a green tick mark if all the checks succeeded. If you see a red mark, please correct your code accordingly. ###### Checklist - [ ] Your branch is up-to-date with the `master` branch and tested with latest changes - [ ] Extended the README / documentation, if necessary - [ ] Code compiles correctly ================================================ FILE: scenario_runner/Docs/FAQ.md ================================================ # Frequently Asked Questions ## I receive the error "TypeError: 'instancemethod' object has no attribute '__getitem__'" in the agent navigation This issue is most likely caused by an outdated version of the Python Networkx package. Please remove the current installation (e.g. sudo apt-get remove python-networkx) and install it using "pip install --user networkx==2.2". ## No scenario visible and I receive the message "No more scenarios .... Exiting" In case you receive the following output ``` Preparing scenario: FollowLeadingVehicle_1 ScenarioManager: Running scenario FollowVehicle Resetting ego-vehicle! Failure! Resetting ego-vehicle! ERROR: failed to destroy actor 527 : unable to destroy actor: not found No more scenarios .... Exiting ``` and you see nothing happening, it is most likely due to the fact, that you did not launch a program to control the ego vehicle. Run for example manual_control.py, and you should now see something happening. ## Scenario Runner exits with error when using --debug commandline parameter In case you receive the following output ``` UnicodeEncodeError: 'ascii' codec can't encode character '\u2713' in position 58: ordinal not in range(128) ``` Please set environment variable ``` PYTHONIOENCODING=utf-8 ``` ================================================ FILE: scenario_runner/Docs/agent_evaluation.md ================================================ #### Setting up your agent for evaluation ## Important: This information is outdated and the challenge files have been removed. This feature has now been moved to the [Leaderboard](https://github.com/carla-simulator/leaderboard). However, it can still be used with the route argument of scenario_runner.py, instead of the challenge_evaluator.py To have your agent evaluated by the challenge evaluation system you must define an Agent class that inherits the [AutonomousAgent](https://github.com/carla-simulator/scenario_runner/blob/master/srunner/autoagents/autonomous_agent.py) base class. In addition, you need to setup your environment as described in the Challenge evaluator tutorial. On your agent class there are three main functions to be overwritten that need to be defined in order to set your agent to run. Further you also should consider the route to the goal that is initially set as a variable. ##### The "setup" function: This is the function where you should make all the necessary setup for the your agent. This function receives as a parameter the path to a configuration file to be parsed by the user. When executing the "challenge_evaluator.py" you should pass the configuration file path as a parameter. For example: ``` python srunner/challenge/challenge_evaluator_routes.py --agent= --config=myconfigfilename.format ``` ##### The "sensors" function: This function is where you set all the sensors required by your agent. For instance, on the dummy agent sample class the following sensors are defined: ```Python def sensors(self): sensors = [{'type': 'sensor.camera.rgb', 'x':0.7, 'y':0.0, 'z':1.60, 'roll':0.0, 'pitch':0.0, 'yaw':0.0, 'width':800, 'height': 600, 'fov':100, 'id': 'Center'}, {'type': 'sensor.camera.rgb', 'x':0.7, 'y':-0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x':0.7, 'y':0.4, 'z':1.60, 'roll':0.0, 'pitch':0.0, 'yaw':45.0, 'width':800, 'height':600, 'fov':100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'id': 'LIDAR'}, {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'}, {'type': 'sensor.speedometer','reading_frequency': 25, 'id': 'speed'} ] return sensors ``` Every sensor is a dictionary where you should specify: * type: basically which is the sensor to be added, for example: 'sensor.camera.rgb' for an rgb camera or 'sensor.lidar.ray_cast' for a ray casting lidar. * id: the label that will be given to the sensor in order for it to be accessed later. * other parameters: these are sensor dependent, such as position, 'x' and 'y', or the field of view for a camera, 'fov' ##### The "run_step" function: This function is called on every step of the simulation from the challenge evaluation an receives some input data as parameter. This input data is a dictionary with all the sensors specified on the "sensors" function. This function should return a [vehicle control](https://carla.readthedocs.io/en/latest/python_api_tutorial/#vehicles) to be applied into the ego vehicle. ##### The initial route: On the beginning of the execution, the entire route that the hero agent should travel is set on the "self.global_plan" variable: ``` [({'z': 0.0, 'lat': 48.99822669411668, 'lon': 8.002271601998707}, ), ({'z': 0.0, 'lat': 48.99822669411668, 'lon': 8.002709765148996}, ), ... ({'z': 0.0, 'lat': 48.99822679980298, 'lon': 8.002735250105061}, )]` ``` It is represented as a list of tuples, containing the route waypoints, expressed in latitude and longitude and the current road option recommended. For an intersection, the option can be go straight, turn left or turn right. For the rest of the route the recommended option is lane follow. ================================================ FILE: scenario_runner/Docs/coding_standard.md ================================================

Coding standard

> _This document is a work in progress and might be incomplete._ General ------- * Use spaces, not tabs. * Avoid adding trailing whitespace as it creates noise in the diffs. * Comments should not exceed 120 columns, code may exceed this limit a bit in rare occasions if it results in clearer code. Python ------ * All code must be compatible with Python 2.7, 3.5, and 3.6. * [Pylint][pylintlink] should not give any error or warning (few exceptions apply with external classes like `numpy`, see our `.pylintrc`). * Python code follows [PEP8 style guide][pep8link] (use `autopep8` whenever possible). [pylintlink]: https://www.pylint.org/ [pep8link]: https://www.python.org/dev/peps/pep-0008/ C++ --- * Compilation should not give any error or warning (`clang++ -Wall -Wextra -std=C++14 -Wno-missing-braces`). * Unreal C++ code (CarlaUE4 and Carla plugin) follow the [Unreal Engine's Coding Standard][ue4link] with the exception of using spaces instead of tabs. * LibCarla uses a variation of [Google's style guide][googlelink]. [ue4link]: https://docs.unrealengine.com/latest/INT/Programming/Development/CodingStandard/ [googlelink]: https://google.github.io/styleguide/cppguide.html ================================================ FILE: scenario_runner/Docs/creating_new_scenario.md ================================================ # Create a new scenario tutorial This tutorial describes how you can create and run a new scenario using the ScenarioRunner and the ScenarioManager suite. Let us call the new scenario _NewScenario_. To create it, there are only few steps required. ## Creating an empty Python class Go to the Scenarios folder and create a new Python class with the name _NewScenario_ in a new Python file (_new_scenario.py_). The class should be derived from the _BasicScenario_ class. As a result, the class should look as follows: ``` class NewScenario(BasicScenario): """ Some documentation on NewScenario :param world is the CARLA world :param ego_vehicles is a list of ego vehicles for this scenario :param config is the scenario configuration (ScenarioConfiguration) :param randomize can be used to select parameters randomly (optional, default=False) :param debug_mode can be used to provide more comprehensive console output (optional, default=False) :param criteria_enable can be used to disable/enable scenario evaluation based on test criteria (optional, default=True) :param timeout is the overall scenario timeout (optional, default=60 seconds) """ # some ego vehicle parameters # some parameters for the other vehicles def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Initialize all parameters required for NewScenario """ # Call constructor of BasicScenario super(NewScenario, self).__init__( name="NewScenario", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable)) def create_behavior(self): """ Setup the behavior for NewScenario """ def create_test_criteria(self): """ Setup the evaluation criteria for NewScenario """ ``` ## Filling the Python class In the NewScenario class, you have to define the following methods mentioned in the code example. ### Initialize Method The initialize method is intended to setup all parameters required for the scenario and all vehicles. This includes selecting the correct vehicles, spawning them at the correct location, etc. To simplify this, you may want to use the _setup_vehicle()_ function defined in basic_scenario.py ### CreateBehavior method This method should setup the behavior tree that contains the behavior of all non-ego vehicles during the scenario. The behavior tree should use py_trees and the atomic behaviors defined in _atomic_scenario_behavior.py_ ### CreateTestCriteria method This method should setup a list with all evaluation criteria for the scenario. The criteria should be based on the atomic criteria defined in _atomic_scenario_criteria.py_. Note: From this list a parallel py_tree will be created automatically! ## Adding the scenario configuration Finally the scenario configuration should be added to the examples/ folder. If you extend an already existing scenario module, you can simply extend the corresponding XML, otherwise add a new XML file. In this case you can use any of the existing XML files as blueprint. If you want to add multiple ego vehicles for a scenario, make sure that they use different role names, e.g. ``` ``` ================================================ FILE: scenario_runner/Docs/extra.css ================================================ .build-buttons{ text-align: center; } .build-buttons > p { display: inline-block; vertical-align: top; padding: 5px; } .vector-zero { text-align: center; } /************************* DEFAULT TABLES **************************/ table.defTable { border: 1px solid #242424; background-color: #f3f6f6; text-align: left; border-collapse: collapse; } table.defTable thead { background: #ffffff; border-bottom: 1px solid #444444; } table.defTable tr:nth-child(even) { background: #ffffff; } table.defTable thead th { padding: 7px 13px; } table.defTable tbody td{ padding: 7px 13px; } /************************* TOWN SLIDER **************************/ * {box-sizing:border-box} /* Container */ .townslider-container { max-width: 1000px; position: relative; margin: auto; } /* Hide the images by default */ .townslide { display: none; text-align: center; } /* Fading animation for slides */ .fade { -webkit-animation-name: fade; -webkit-animation-duration: 1.5s; animation-name: fade; animation-duration: 1.5s; } @-webkit-keyframes fade { from {opacity: .4} to {opacity: 1} } @keyframes fade { from {opacity: .4} to {opacity: 1} } /* "next" and "previous" buttons */ .prev, .next { cursor: pointer; position: absolute; top: 50%; width: auto; margin-top: -22px; padding: 16px; color: white; font-weight: bold; font-size: 18px; transition: 0.6s ease; border-radius: 0 3px 3px 0; user-select: none; } /* Position the "next" button*/ .next { right: 0; border-radius: 3px 0 0 3px; } /* Black background color to buttons when hovering*/ .prev:hover, .next:hover { background-color: rgba(0,0,0,0.8); } /* Caption text for towns */ .text { color: #f2f2f2; font-size: 15px; padding: 8px 12px; position: absolute; bottom: 8px; width: 100%; text-align: center; /*background-color:rgba(0,0,0,0.5);*/ } /* The dot indicators for slides */ .dot { cursor: pointer; height: 15px; width: 15px; margin: 0 2px; background-color: #bbb; border-radius: 50%; display: inline-block; transition: background-color 0.6s ease; } .active, .dot:hover { background-color: #717171; } ================================================ FILE: scenario_runner/Docs/getting_scenariorunner.md ================================================ # Get ScenarioRunner This tutorial explains how to download ScenarioRunner and run a simple example to test it. ScenarioRunner needs CARLA in order to run, and must match the CARLA version being used. If the CARLA being used is a build from source, download ScenarioRunner from source. If the CARLA being used is a package, download the corresponding version of ScenarioRunner. * __[Installation summary](#installation-summary)__ * __[A. Download a ScenarioRunner release](#a.-download-a-scenariorunner-release)__ * [Update the release](#update-the-release) * __[B. Download ScenarioRunner from source](#b.-build-scenariorunner-from-source)__ * [Update the build from source](#update-the-build-from-source) * __[Run a test](#run-a-test)__ --- ## Installation summary
Show command line summary for the quick start installation ```sh # Decide whether to use a package or make the build from source # Option A) Use a ScenarioRunner package # 1. Install a CARLA package: https://carla.readthedocs.io/en/latest/start_quickstart/ # 2. Download the matching ScenarioRunner package: https://github.com/carla-simulator/scenario_runner/releases # 3. Extract the content wherever needed. # Update the release: # 1. Delete previous CARLA and ScenarioRunner versions. # 2. Download the latest CARLA release. # 3. Download the matching ScenarioRunner release. # Option B) Download ScenarioRunner from source # 1. Build CARLA from source: https://carla.readthedocs.io/en/latest/build_linux/ # 2. Clone the ScenarioRunner repository: git clone https://github.com/carla-simulator/scenario_runner.git # 3. Install requirements according to the Python version to be used: # For Python 2.x: sudo apt remove python-networkx #if installed, remove old version of networkx pip2 install --user -r requirements.txt # For Python 3.x: sudo apt remove python3-networkx #if installed, remove old version of networkx pip3 install --user -r requirements.txt # To update ScenarioRunner from source: # 1. Update CARLA: https://carla.readthedocs.io/en/latest/build_update/ # 2. Go to the ScenarioRunner repository, master branch cd ~/scenario_runner git branch master # 3. Pull the latest changes from the repository git pull ```
--- ## A. Download a ScenarioRunner release The releases of ScenarioRunner are packages containing: * A ScenarioRunner version tied to a specific CARLA release. * A few example scenarios written in Python. The process to run a ScenarioRunner release is quite straightforward. __1. Download a CARLA release.__ Follow the process in the [CARLA quick start](https://github.com/carla-simulator/carla/releases). __2. Download the matching ScenarioRunner release.__ All of the releases are listed [here](https://github.com/carla-simulator/scenario_runner/releases). !!! Important Both versions have to match. If the CARLA release is *0.9.9*, use also ScenarioRunner *0.9.9*. [Here](https://github.com/carla-simulator/scenario_runner) is a brief list of compatibilities between CARLA and ScenarioRunner. __3. Extract the content.__ The directory does not matter. ### Update the release The packaged version requires no updates. The content is bundled and thus, tied to a specific release of CARLA. Everytime there is a new CARLA release, there will be a matching one for ScenarioRunner. All the releases are listed here: * [CARLA releases](https://github.com/carla-simulator/carla/releases) * [Scenario Runner releases](https://github.com/carla-simulator/scenario_runner/releases) To run the latest or any other release, delete the previous and install the one desired. --- ## B. Download ScenarioRunner from source The ScenarioRunner source repository contains the most experimental features that run with the latest development version of CARLA. It requires no build, as it only contains Python code for the ScenarioRunner module. __1. Build CARLA from source.__ Follow the docs to build on [Linux](https://carla.readthedocs.io/en/latest/build_linux/) or [Windows](https://carla.readthedocs.io/en/latest/build_windows/). !!! Important ScenarioRunner needs CARLA to run, so the minimum requirements for CARLA stated in the docs are also necessary to run ScenarioRunner. __2. Clone the ScenarioRunner repository.__ ```sh git clone https://github.com/carla-simulator/scenario_runner.git ``` __3. Install the requirements according to the Python version to be used.__ First go to the main ScenarioRunner directory ```sh cd ~/scenario_runner/ ``` * __For Python 2.x.__ ```sh sudo apt remove python-networkx #if installed, remove old version of networkx pip2 install --user -r requirements.txt ``` * __For Python 3.x__ ```sh sudo apt remove python3-networkx #if installed, remove old version of networkx pip3 install --user -r requirements.txt ``` !!! Warning py-trees newer than v0.8 are __not__ supported. ### Update from source __1. Update the CARLA build__ Follow the [docs](https://carla.readthedocs.io/en/latest/build_update/) to update CARLA. __2. Go to the main ScenarioRunner directory.__ Make sure to be in the local master branch. ```sh cd ~/scenario_runner git branch master ``` __3. Pull the latest changes from the repository.__ ```sh git pull ``` __4. Add environment variables and Python paths__ These are necessary for the system to find CARLA, and add the PythonAPI to the Python path. * __For Linux__ ```sh # ${CARLA_ROOT} is the CARLA installation directory # ${SCENARIO_RUNNER} is the ScenarioRunner installation directory # is the correct string for the Python version being used # In a build from source, the .egg files may be in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI export CARLA_ROOT=/path/to/your/carla/installation export SCENARIO_RUNNER_ROOT=/path/to/your/scenario/runner/installation export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-.egg export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/agents export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI ``` !!! Note Change the command lines with the proper paths, according to the comments. * __For Windows__ ```sh # %CARLA_ROOT% is the CARLA installation directory # %SCENARIO_RUNNER% is the ScenarioRunner installation directory # is the correct string for the Python version being used # In a build from source, the .egg files may be in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI set CARLA_ROOT=\path\to\your\carla\installation set SCENARIO_RUNNER_ROOT=\path\to\your\scenario\runner\installation set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla\dist\carla-.egg set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla\agents set PYTHONPATH=%PYTHONPATH%;%CARLA_ROOT%\PythonAPI\carla set PYTHONPATH=%PYTHONPATH%:%CARLA_ROOT%\PythonAPI ``` !!! Note Change the command lines with the proper paths, according to the comments. To permanently set the environment variables, go to *edit the environment variables of this account*. This can be quickly accessed by writing *env* on the Windows' search panel. --- ## Run a test Running the follow vehicle example First of all, you need to get latest master branch from CARLA. Then you have to include CARLA Python API to the Python path: !!! Important If working with builds from source, make sure to upload these. Download the latest content in the master branches. __1. Run the CARLA server.__ * __A) In a build from source__ go to the CARLA directory and launch the server in the editor. ```sh cd ~/carla # Change the path accordingly make launch # Press Play in the UE Editor ``` * __B) In a CARLA package__ run the server directly. ```sh ./CarlaUE4.sh ``` __2. Start an example scenario.__ Open another terminal and go to the directory where ScenarioRunner is downloaded. For the sake of this test, the follow leading vehicle scenario will be used. ```sh # Inside the ScenarioRunner root directory python scenario_runner.py --scenario FollowLeadingVehicle_1 --reloadWorld ``` !!! Note If using a Python 3.x version, run the command with `python3`. __3. Test the scenario with manual control.__ Open a new terminal and run the `manual_control.py`. A new window should pop up, with an ego vehicle in the middle of the street. Move forward and the leading vehicle will appear. ```sh # Inside the ScenarioRunner root directory python manual_control.py ``` The scenarios have a timeout of one minute approximately, for the agent to be launched. If the timeout appears, the follow leading vehicle example should be launched again. !!! Warning Run the `manual_control.py` found in the ScenarioRunner package/repository, __not CARLA__. __4. Explore other options.__ Run the Scenario Runner with the flag `--help` to explore other command line parameters and some basic descriptions. For example, to avoid automatically (re-)load the CARLA world, skip the command line option `--reloadWorld`. ```sh python scenario_runner.py --help ``` --- Thus concludes the installation process for ScenarioRunner. In case any unexpected error or issue occurs, the [CARLA forum](https://forum.carla.org/c/using-carla/scenario-runner) is open to everybody. There is an _ScenarioRunner_ category to post problems and doubts regarding this module. ================================================ FILE: scenario_runner/Docs/getting_started.md ================================================ # Getting Started Tutorial !!! important This tutorial refers to the latest versions of CARLA (at least 0.9.5) Welcome to the ScenarioRunner for CARLA! This tutorial provides the basic steps for getting started using the ScenarioRunner for CARLA. Download the latest release from our GitHub page and extract all the contents of the package in a folder of your choice. The release package contains the following * The ScenarioRunner for CARLA * A few example scenarios written in Python. ## Installing prerequisites The current version is designed to be used with Ubuntu 16.04, Python 2.7 or Python 3.5. Depending on your Python version, execute: ``` #Python 2.x sudo apt remove python-networkx #if installed, remove old version of networkx pip2 install --user -r requirements.txt #Python 3.x sudo apt remove python3-networkx #if installed, remove old version of networkx pip3 install --user -r requirements.txt ``` Note: py-trees newer than v0.8 is *NOT* supported. ## Running the follow vehicle example First of all, you need to get latest master branch from CARLA. Then you have to include CARLA Python API to the Python path: ```Bash export CARLA_ROOT=/path/to/your/carla/installation export PYTHONPATH=$PYTHONPATH:${CARLA_ROOT}/PythonAPI/carla/dist/carla-.egg:${CARLA_ROOT}/PythonAPI/carla/agents:${CARLA_ROOT}/PythonAPI/carla ``` NOTE: ${CARLA_ROOT} needs to be replaced with your CARLA installation directory, and needs to be replaced with the correct string. If you build CARLA from source, the egg files maybe located in: ${CARLA_ROOT}/PythonAPI/dist/ instead of ${CARLA_ROOT}/PythonAPI. Now, you can start the CARLA server from ${CARLA_ROOT} ``` ./CarlaUE4.sh ``` Start the example scenario (follow a leading vehicle) in an extra terminal: ``` python scenario_runner.py --scenario FollowLeadingVehicle_1 --reloadWorld ``` If you require help or want to explore other command line parameters, start the scenario runner as follows: ``` python scenario_runner.py --help ``` To control the ego vehicle within the scenario, open another terminal and run: ``` python manual_control.py ``` Note: If you do not wish to automatically (re-)load the CARLA world, you can skip the command line option _--reloadWorld_ ## Running all scenarios of one scenario class Similar to the previous example, it is also possible to execute a sequence of scenarios, that belong to the same class, e.g. the "FollowLeadingVehicle" class. The only difference is, that you start the scenario_runner as follows: ``` python scenario_runner.py --scenario group:FollowLeadingVehicle ``` ## Running other scenarios A list of supported scenarios is provided in [List of Supported Scenarios](list_of_scenarios.md). Please note that different scenarios may take place in different CARLA towns. This has to be respected when launching the CARLA server. ## Running scenarios using the OpenSCENARIO format To run a scenario, which is based on the OpenSCENARIO format, please run the ScenarioRunner as follows: ``` python scenario_runner.py --openscenario ``` Please note that the OpenSCENARIO support and the OpenSCENARIO format itself are still work in progress. More information you can find in [OpenSCENARIO support](openscenario_support.md) ## Running route-based scenario (similar to the CARLA AD Challenge) To run a route-based scenario, please run the ScenarioRunner as follows: ``` python scenario_runner.py --route [route id] --agent ``` Example: ``` python scenario_runner.py /scenario_runner/srunner/routes_debug.xml /scenario_runner/srunner/data/all_towns_traffic_scenarios1_3_4.json 0 --agent srunner/autoagents/npc_agent.py ``` If no route id is provided, all routes within the given file will be executed. By doing so, ScenarioRunner will match the scenarios to the route, and they'll activate when the ego vehicle is nearby. However, routes need an autonomous agent to control the ego vehicle. Several examples are provided in srunner/autoagents/. For more information about agents, please have a look into the [agent documentation](agent_evaluation.md) ================================================ FILE: scenario_runner/Docs/index.md ================================================ [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) ![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/carla-simulator/scenario_runner.svg) [![Build Status](https://travis-ci.com/carla-simulator/scenario_runner.svg?branch=master)](https://travis-ci.com/carla/scenario_runner) # ScenarioRunner ScenarioRunner is a module that allows traffic scenario definition and execution for the [CARLA](http://carla.org/ ) simulator. The scenarios can be defined through a Python interface or using the [OpenSCENARIO](http://www.openscenario.org/) standard. ScenarioRunner can also be used to prepare AD agents for their evaluation, by easily creating complex traffic scenarios and routes for the agents to navigate through. These results can be validated and shared in the [CARLA Leaderboard](https://leaderboard.carla.org/), an open platform for the community to fairly compare their progress, evaluating agents in realistic traffic situatoins. The CARLA forum has a specific section regarding ScenarioRunner, for users to post any doubts or suggestions that may arise during the reading of this documentation. --- ## Quick start

[__Get ScenarioRunner__](getting_scenariorunner.md) — Tutorial on how to download and launch ScenarioRunner. [__First steps__](getting_started.md) — Brief tutorials on how to run different types of scenarios. [__Create a new scenario__](creating_new_scenario.md) — Tutorial on how to create a new scenario using ScenarioRunner. [__Metrics module__](metrics_module.md) — Explanation of the metrics module. [__F.A.Q.__](FAQ.md) — Some of the most frequent installation issues. [__Release notes__](CHANGELOG.md) — Features, fixes and other changes listed per release.

## References

[__List of scenarios__](list_of_scenarios.md) — Example scenarios available in ScenarioRunner. [__OpenScenario support__](getting_started.md) — Support status of OpenSCENARIO features.

## Contributing

[__Code of conduct__](CODE_OF_CONDUCT.md) — Standard rights and duties for contributors. [__Coding standard__](coding_standard.md) — Guidelines to write proper code. [__Contribution guidelines__](CONTRIBUTING.md) — The different ways to contribute to ScenarioRunner.

================================================ FILE: scenario_runner/Docs/list_of_scenarios.md ================================================ # List of Supported Scenarios Welcome to the ScenarioRunner for CARLA! This document provides a list of all currently supported scenarios, and a short description for each one. ### FollowLeadingVehicle The scenario realizes a common driving behavior, in which the user-controlled ego vehicle follows a leading car driving down a given road in Town01. At some point the leading car slows down and finally stops. The ego vehicle has to react accordingly to avoid a collision. The scenario ends either via a timeout, or if the ego vehicle stopped close enough to the leading vehicle ### FollowLeadingVehicleWithObstacle This scenario is very similar to 'FollowLeadingVehicle'. The only difference is, that in front of the leading vehicle is a (hidden) obstacle that blocks the way. ### VehicleTurningRight In this scenario the ego vehicle takes a right turn from an intersection where a cyclist suddenly drives into the way of the ego vehicle,which has to stop accordingly. After some time, the cyclist clears the road, such that ego vehicle can continue driving. ### VehicleTurningLeft This scenario is similar to 'VehicleTurningRight'. The difference is that the ego vehicle takes a left turn from an intersection. ### OppositeVehicleRunningRedLight In this scenario an illegal behavior at an intersection is tested. An other vehicle waits at an intersection, but illegally runs a red traffic light. The approaching ego vehicle has to handle this situation correctly, i.e. despite of a green traffic light, it has to stop and wait until the intersection is clear again. Afterwards, it should continue driving. ### StationaryObjectCrossing In this scenario a cyclist is stationary waiting in the middle of the road and blocking the way for the ego vehicle. Hence, the ego vehicle has to stop in front of the cyclist. ### DynamicObjectCrossing This is similar to 'StationaryObjectCrossing', but with the difference that the cyclist is dynamic. It suddenly drives into the way of the ego vehicle, which has to stop accordingly. After some time, the cyclist will clear the road, such that the ego vehicle can continue driving. ### NoSignalJunctionCrossing This scenario tests negotiation between two vehicles crossing cross each other through a junction without signal. The ego vehicle is passing through a junction without traffic lights And encounters another vehicle passing across the junction. The ego vehicle has to avoid collision and navigate across the junction to succeed. ### ControlLoss In this scenario control loss of a vehicle is tested due to bad road conditions, etc and it checks whether the vehicle is regained its control and corrected its course. ### ManeuverOppositeDirection In this scenario vehicle is passing another vehicle in a rural area, in daylight, under clear weather conditions, at a non-junction and encroaches into another vehicle traveling in the opposite direction. ### OtherLeadingVehicle The scenario realizes a common driving behavior, in which the user-controlled ego vehicle follows a leading car driving down a given road. At some point the leading car has to decelerate. The ego vehicle has to react accordingly by changing lane to avoid a collision and follow the leading car in other lane. The scenario ends via timeout, or if the ego vehicle drives certain distance. ### SignalizedJunctionRightTurn In this scenario right turn of hero actor without collision at signalized intersection is tested. Hero Vehicle is turning right in an urban area, at a signalized intersection and turns into the same direction of another vehicle crossing straight initially from a lateral direction. ### SignalizedJunctionLeftTurn In this scenario hero vehicle is turning left in an urban area, at a signalized intersection and cuts across the path of another vehicle coming straight crossing from an opposite direction. ================================================ FILE: scenario_runner/Docs/metrics_module.md ================================================ # Metrics module The metrics module relies on the [CARLA recorder](https://carla.readthedocs.io/en/latest/adv_recorder/) to facilitate the easy calculus and monitoring of any kind of parameter. After the scenario is finished, the recorder stores the simulation information. Users can then define their own metrics, and check the corresponding results with no need to play the simulation again and again. This section covers an explanation of the different elements that form the module, a step by step tutorial of how to create a new metric, and a reference of the functions that query the recording and define the metrics. * [__Structure of the module__](#structure-of-the-module) * [__How to use the metrics module__](#how-to-use-the-metrics-module) * [1. Record a scenario](#1.-record-a-scenario) * [2. Define the metrics](#2.-run-the-metrics-manager) * [3. Run the metrics manager](#3.-run-the-metrics-manager) * [__Recording queries reference__](#recording-queries-reference) * [Generic actor data](#generic-actor-data) * [Generic simulation data](#generic-simulation-data) * [Actor accelerations](#actor-accelerations) * [Actor angular velocities](#actor-angular-velocities) * [Actor controls](#actor-controls) * [Actor transforms](#actor-transforms) * [Actor velocities](#actor-velocities) * [Scene lights](#scene-lights) * [Traffic lights](#traffic-lights) * [Vehicle lights](#vehicle-lights) --- ## Structure of the module Similarly to the main ScenarioRunner module, the Metrics module is run using a main script, `metrics_manager.py`, and the rest of the information is contained inside a folder structure. Here is a brief introduction to the main script. * __`metrics_manager.py`__ — The main script of the module. Run this to show the results of the set of metrics. The script has the usual `host` and `port` arguments, and some more to set the metrics and recording to be used. * `host` *(string)* – IP address where a CARLA simulation is running. Default is `(127.0.0.1)`. * `port` *(int)* – TCP port where the CARLA simulation is running. Default are `2000` and `2001`. * `metrics` — Path to the metrics to be used. * `log` — Path to the `.log` file containing the recording (relative to the environment variable `SCENARIO_RUNNER_ROOT`). * `criteria` *(optional)* — Path to a JSON file with the criteria of the scenario. The rest of the elements that shape the module can be found in the `srunner/metrics` folder. These folder has been divided in three subfolders. * __`srunner/metrics/data`__ — Stores information about the scenarios. By default, it has six files, which are part of the examples metric. * __`srunner/metrics/examples`__ — Contains some example metrics, and the metric containing the base class `BaseMetric` to create new metrics. * `basic_metric.py` – Contains the base class `BaseMetric`. All the metrics are inherited from it. * `criteria_filter.py` – Returns a JSON with the most important attributes of the criteria. * `distance_between_vehicles.py` – Returns the distance betwen two vehicles. Useful to show how to query the recording. * `distance_to_lane_center.py` – Calculates the distance between the vehicle location and the center of the lane. Useful to show how to access the map API information.. * __`srunner/metrics/tools`__ — Contains two key scripts that allow to query the recording. * `metrics_parser.py` – Transforms the string provided by the recording to a dictionary. * `metrics_log.py` – Provides with several functions to query the dictionary created with `metrics_parser.py`. These functions are the easiest way to access information of a scenario. They listed in a [reference](#recording-queries-reference) in the last segment of this page. --- ## How to use the metrics module ### 1. Record a scenario The metrics module needs for a recording of a simulation in order to work. Otherwise, it has no data to make the calculations of the metrics. Use the `record` argument. Add the path where the information should be saved should be saved. The path must be relative to the environment variable `SCENARIO_RUNNER_ROOT`. ```sh python scenario_runner.py --scenario --record ``` By recording the scenario two files will be created in the desired path. These files will later be used as the `log` and `criteria` arguments in the `metrics_manager.py`. __1. A CARLA recording__ *(`.log`)* — Contains simulation data per frame. To know more about this, read the [recorder docs](https://carla.readthedocs.io/en/latest/adv_recorder/). __2. A criteria file__ *(.json)* — The criteria of the scenario parsed as a dictionary, and stored in a JSON file. The keys of the dictionary are the names of the criteria. The values are the attributes of each criteria. !!! Note Only the JSON serializable attributes will be parsed, the rest will be ignored. By default, both files are named after the scenario that is run. If the scenario is named `example.py`, the files will be `example.log` and `example.json`. ### 2. Define the metrics It is time to create the desired metrics that will be used for the scenario. The possibilities are endless, but for the sake of this tutorial, the metric described in `srunner/metrics/examples/distance_between_vehicles.py` will be used as an example. Let's dig a little bit into the code itself. class DistanceBetweenVehicles(BasicMetric): """ Metric class DistanceBetweenVehicles """ def _create_metric(self, town_map, log, criteria): """ Implementation of the metric. This is an example to show how to use the recorder, accessed via the log. """ # Get the ID of the two vehicles ego_id = log.get_ego_vehicle_id() adv_id = log.get_actor_ids_with_role_name("scenario")[0] # Could have also used its type_id dist_list = [] frames_list = [] # Get the frames both actors were alive start_ego, end_ego = log.get_actor_alive_frames(ego_id) start_adv, end_adv = log.get_actor_alive_frames(adv_id) start = max(start_ego, start_adv) end = min(end_ego, end_adv) # Get the distance between the two for i in range(start, end): # Get the transforms ego_location = log.get_actor_transform(ego_id, i).location adv_location = log.get_actor_transform(adv_id, i).location # Filter some points for a better graph if adv_location.z < -10: continue dist_v = ego_location - adv_location dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z) dist_list.append(dist) frames_list.append(i) # Use matplotlib to show the results plt.plot(frames_list, dist_list) plt.ylabel('Distance [m]') plt.xlabel('Frame number') plt.title('Distance between the ego vehicle and the adversary over time') plt.show() __2.1. Name the metric__. First of all, as it was previously mentioned, all metrics are childs of the `BasicMetric` class. ```py class DistanceBetweenVehicles(BasicMetric): ``` __2.2. Name the main method__. A metric only requires one method in order to run, `_create_metric()`, which has three arguments. * __`town_map`__ — Instance of the [carla.Map()](https://carla.readthedocs.io/en/latest/python_api/#carlamap) where the scenario took place in. * __`log`__ — Instance to the `MetricsLog` class, with all the functions needed to access the recorder dictionary. * __`criteria`__ — A JSOn with the criteria dictionary. The file provided when recording a scenario that is later provided to the `metrics_manager.py`. ```py def _create_metric(self, town_map, log, criteria): ``` __2.3. Implement the metric__. The code will vary depending on the metric itself. The example metric `DistanceBetweenVehicles` calculates the distance between the ego vehicle, and the car it follows (adversary). To do so, it needs the `id` of the two vehicles. These can be retrieved from the log using the `get_ego_vehicle_id()` and `get_actor_ids_with_role_name("scenario")[0]` functions. ```py # Get the ID of the two vehicles ego_id = log.get_ego_vehicle_id() adv_id = log.get_actor_ids_with_role_name("scenario")[0] # Could have also used its type_id ``` The `id` are used to retrieve the frames where the vehicles were alive using `get_actor_alive_frames(actor_id)`. ```py # Get the frames both actors were alive start_ego, end_ego = log.get_actor_alive_frames(ego_id) start_adv, end_adv = log.get_actor_alive_frames(adv_id) start = max(start_ego, start_adv) end = min(end_ego, end_adv) ``` Now everything is ready to loop through those frames, get their transforms, and calculate the distance. To get the transform, `get_actor_transform(actor_id, frame)` is used. ```py dist_list = [] frames_list = [] ... # Get the distance between the two for i in range(start, end): # Get the transforms ego_location = log.get_actor_transform(ego_id, i).location adv_location = log.get_actor_transform(adv_id, i).location # Filter some points for a better graph if adv_location.z < -10: continue dist_v = ego_location - adv_location dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z) dist_list.append(dist) ``` !!! Note The vertical condition of the adversary is to only take into account the adversary when it is driving normally. Lastly, use [matplotlib](https://matplotlib.org/) to define which should be the output of the metric when running `metrics_manager.py`. ```py # Use matplotlib to show the results plt.plot(frames_list, dist_list) plt.ylabel('Distance [m]') plt.xlabel('Frame number') plt.title('Distance between the ego vehicle and the adversary over time') plt.show() ``` ### 3. Run the metrics manager Finally it is time to used the information retrieve from the scenario, and the metrics that have been defined to return some metrics information. Let's run the module using the example metric that has been used so far, and an example log named after it. ```sh python metrics_manager.py --metric srunner/metrics/examples/distance_between_vehicles.py --log srunner/metrics/data/DistanceBetweenVehicles.log ``` !!! Warning A simulation must be running. Otherwise, the module will not be able to acces the map API. This will create a new window with the results plotted. The script will not finish until the ouput window is closed. ![metrics_plot](img/metrics_example.jpg) --- ## Recording queries reference When defining a metric, all the information about the scenario is accessed via the `MetricsLog` class (the `log` argument at the `_create_metric()` function). This class is located at `srunner/metrics/tools/metrics_log.py`, and this reference is a following of the functions contained in it. ### Generic actor data - __get_ego_vehicle_id__(__self__) Returns the `id` of the ego vehicle. - __Return —__ int - __get_actor_ids_with_role_name__(__self__, __role_name__) Returns a list of actor `id` that match the given `role_name`. - __Return —__ list - __Parameters__ - `role_name` (_str_) — `role_name` of the actor. - __get_actor_ids_with_type_id__(__self__, __type_id__) Returns a list of actor `id` that match the given `type_id`, according to fnmatch standard. - __Return —__ list - __Parameters__ - `type_id` (_str_) — `type_id` of the actor. - __get_actor_attributes__(__self__, __actor_id__) Returns a dictionary with all the attributes of an actor. - __Return —__ dict - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - __get_actor_bounding_box__(__self__, __actor_id__) Returns the bounding box of the specified actor. - __Return —__ [carla.BoundingBox](https://carla.readthedocs.io/en/latest/python_api/#carlaboundingbox) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - __get_traffic_light_trigger_volume__(__self__, __traffic_light_id__) Returns the trigger volume of the specified traffic light. - __Return —__ [carla.BoundingBox](https://carla.readthedocs.io/en/latest/python_api/#carlaboundingbox) - __Parameters__ - `traffic_light_id` (_int_) — `id` of the traffic light. - __get_actor_alive_frames__(__self__, __actor_id__) Returns a tuple with the first and last frame an actor was alive. Note that frames start at 1, not 0. - __Return —__ tuple - __Parameters__ - `actor_id` (_int_) — `id` of the actor. ### Generic simulation data - __get_collisions__(__self__,__actor_id__) Returns a list of dictionaries with two keys. `frame` is the frame number of the collision, and `other_id`, a list of the ids the actor collided with at that frame. - __Return —__ list - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - __get_total_frame_count__(__self__) Returns an int with the total amount of frames the simulation lasted. - __Return —__ int - __get_elapsed_time__(__self__, __frame__) Returns a float with the elapsed time of a specific frame. - __Return —__ float - __Parameters__ - `frame` (_int_) — Frame number. - __get_delta_time__(__self__, __frame__) Returns an float with the delta time of a specific frame. - __Return —__ float - __Parameters__ - `frame` (_int_) — Frame number. - __get_platform_time__(__self__, __frame__) Returns a float with the platform time of a specific frame. - __Return —__ float - __Parameters__ - `frame` (_int_) — Frame number. ### Actor accelerations - __get_actor_acceleration__(__self__, __actor_id__, __frame__) Returns the acceleration of the actor at a given frame. Returns None if the actor `id` doesn't exist, the actor has no acceleration, or the actor wasn't alive at that frame. - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `frame` (_int_) — Frame number. - __get_all_actor_accelerations__(__self__, __actor_id__, __first_frame__=None, __last_frame__=None) Returns a list with all the accelerations of the actor at the frame interval. By default, the frame interval comprises all the recording. - __Return —__ list(carla.Vector3D) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation. - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation. - __get_actor_accelerations_at_frame__(__self__, __frame__, __actor_list__=None) Returns a dict where the keys are the frame number, and the values are the carla.Vector3D of the actor at the given frame. By default, all actors are considered but if *actor_list* is passed, only actors in the list will be checked. - __Return —__ list(carla.Vector3D) - __Parameters__ - `frame` (_int_) — Frame number. - `actor_list` (_int_) — List of actor `id`. ### Actor angular velocities - __get_actor_angular_velocity__(__self__, __actor_id__, __frame__) Returns the angular velocity of the actor at a given frame. Returns None if the actor id doesn't exist, the actor has no angular velocity, or the actor wasn't alive at that frame. - __Return —__ carla.Vector3D - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `frame` (_int_) — Frame number. - __get_all_actor_angular_velocities__(__self__, __actor_id__, __first_frame__=None, __last_frame__=None) Returns a list with all the angular velocities of the actor at the frame interval. By default, the frame interval comprises all the recording. - __Return —__ list(carla.Vector3D) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation. - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation. - __get_actor_angular_velocities_at_frame__(__self__, __frame__, __actor_list__=None) Returns a dictionary where the keys are the frame number, and the values are the [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d) of the actor at the given frame. By default, all actors are considered but if `actor_list` is passed, only actors in the list will be checked. - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)) - __Parameters__ - `frame` (_int_) — frame number. - `actor_list` (_int_) — List of actor ids. ### Actor controls - __get_vehicle_control__(__self__, __vehicle_id__, __frame__) Returns the control of a vehicle at a given frame. The `manual_gear_shift` attribute will always be False. - __Return —__ [carla.VehicleCotnrol](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclecontrol) - __Parameters__ - `vehicle_id` (_int_) — `id` of the vehicle. - `frame` (_int_) — Frame number. - __get_vehicle_physics_control__(__self__, __vehicle_id__, __frame__) Returns the physics control of a vehicle at a given frame. - __Return —__ [carla.VehiclePhysicsControl](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclephysicscontrol) - __Parameters__ - `vehicle_id` (_int_) — `id` of the vehicle. - `frame` (_int_) — Frame number. - __get_walker_speed__(__self__, __walker_id__, __frame__) Returns the speed of a walker at a given frame. - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d) - __Parameters__ - `walker_id` (_int_) — `id` of the walker. - `frame` (_int_) — Frame number. ### Actor transforms - __get_actor_transform__(__self__, __actor_id__, __frame__) Returns the transform of the actor at a given frame. Returns None if the actor id doesn't exist, the actor has no transform, or the actor wasn't alive at that frame. - __Return —__ [carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `frame` (_int_) — Frame number. - __get_all_actor_transforms__(__self__, __actor_id__, __first_frame__=None, __last_frame__=None) Returns a list with all the transforms of the actor at the frame interval. By default, the frame interval comprises all the recording. - __Return —__ list([carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform)) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation. - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation. - __get_actor_transforms_at_frame__(__self__, __frame__, __actor_list__=None) Returns a dictionary where the keys are the frame number, and the values are the [carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform) of the actor at the given frame. By default, all actors are considered but if `actor_list` is passed, only actors in the list will be checked. - __Return —__ list([carla.Transform](https://carla.readthedocs.io/en/latest/python_api/#carlatransform)) - __Parameters__ - `frame` (_int_) — Frame number. - `actor_list` (_int_) — List of actor `id`. ### Actor velocities - __get_actor_velocity__(__self__, __actor_id__, __frame__) Returns the velocity of the actor at a given frame. Returns None if the actor id doesn't exist, the actor has no velocity, or the actor wasn't alive at that frame. - __Return —__ [carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `frame` (_int_) — Frame number. - __get_all_actor_velocities__(__self__, __actor_id__, __first_frame__=None, __last_frame__=None) Returns a list with all the velocities of the actor at the frame interval. By default, the frame interval comprises all the recording. - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d)) - __Parameters__ - `actor_id` (_int_) — `id` of the actor. - `first_frame` (_int_) — Initial frame of the interval. By default, the start of the simulation. - `last_frame` (_int_) — Last frame of the interval. By default, the end of the simulation. - __get_actor_velocities_at_frame__(__self__, __frame__, __actor_list__=None) Returns a dict where the keys are the frame number, and the values are the carla.Vector3D of the actor at the given frame. By default, all actors are considered but if *actor_list* is passed, only actors in the list will be checked. - __Return —__ list([carla.Vector3D](https://carla.readthedocs.io/en/latest/python_api/#carlavector3d) - __Parameters__ - `frame` (_int_) — Frame number. - `actor_list` (_int_) — List of actor `id`. ### Scene lights - __get_scene_light_state__(__self__, __light__, __vehicle_id__, __frame__) Returns the state of a scene light for a given frame. The light state group will always be [carla.LightGroup.None](https://carla.readthedocs.io/en/latest/python_api/#carlalightgroup). - __Return —__ carla.LightState - __Parameters__ - `light_id` (_int_) — `id` of the scene light. - `frame` (_int_) — Frame number. ### Traffic lights - __get_traffic_light_state__(__self__, __traffic_light_id__, __frame__) Returns the state of a traffic light at a given frame. - __Return —__ [carla.TrafficLightState](https://carla.readthedocs.io/en/latest/python_api/#carlatrafficlightstate). - __Parameters__ - `traffic_light_id` (_int_) — `id` of the traffic light. - `frame` (_int_) — Frame number. - __is_traffic_light_frozen__(__self__, __traffic_light_id__, __frame__) Returns whether or not a traffic light is frozen at a given frame. - __Return —__ bool - __Parameters__ - `traffic_light_id` (_int_) — `id` of the traffic light. - `frame` (_int_) — Frame number. - __get_traffic_light_elapsed_time__(__self__, __traffic_light_id__, __frame__) Returns the elapsed time of a traffic light at a given frame. - __Return —__ float - __Parameters__ - `traffic_light_id` (_int_) — `id` of the traffic light. - `frame` (_int_) — Frame number. - __get_traffic_light_state_time__(__self__, __traffic_light_id__, __state__, __frame__) Returns the maximum time of a specific state of a traffic light at a given frame. - __Return —__ float - __Parameters__ - `traffic_light_id` (_int_) — `id` of the traffic light. - `state` ([carla.TrafficLightState](https://carla.readthedocs.io/en/latest/python_api/#carlatrafficlightstate)) — `id` of the actor. - `frame` (_int_) — Frame number. ### Vehicle lights - __get_vehicle_lights__(__self__, __vehicle_id__, __frame__) Returns a list with the active lights of a specific vehicle at a given frame. - __Return —__ list([carla.VehicleLightState](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclelightstate)) - __Parameters__ - `vehicle_id` (_int_) — `id` of the vehicle. - `frame` (_int_) — Frame number. - __is_vehicle_light_active__(__self__, __light__, __vehicle_id__, __frame__) Checks whether or not a given vehicle light is active for a vehicle at a specific frame. - __Return —__ bool - __Parameters__ - `light` ([carla.VehicleLightState](https://carla.readthedocs.io/en/latest/python_api/#carlavehiclelightstate)) — The light state to be compared with the vehicle. - `vehicle_id` (_int_) — `id` of the vehicle. - `frame` (_int_) — Frame number. ================================================ FILE: scenario_runner/Docs/openscenario_support.md ================================================ ## OpenSCENARIO Support The scenario_runner provides support for the [OpenSCENARIO](http://www.openscenario.org/) 1.0 standard. The current implementation covers initial support for maneuver Actions, Conditions, Stories and the Storyboard. If you would like to use evaluation criteria for a scenario to evaluate pass/fail results, these can be implemented as StopTriggers (see below). However, not all features for these elements are yet available. If in doubt, please see the module documentation in srunner/tools/openscenario_parser.py An example for a supported scenario based on OpenSCENARIO is available [here](https://github.com/carla-simulator/scenario_runner/blob/master/srunner/examples/FollowLeadingVehicle.xosc) In addition, it is recommended to take a look into the official documentation available [here](https://releases.asam.net/OpenSCENARIO/1.0.0/Model-Documentation/index.html) and [here](https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#_foreword). ### Migrating OpenSCENARIO 0.9.x to 1.0 The easiest way to convert old OpenSCENARIO samples to the official standard 1.0 is to use _xsltproc_ and the migration scheme located in the openscenario folder. Example: ```bash xsltproc -o newScenario.xosc migration0_9_1to1_0.xslt oldScenario.xosc ``` ### Level of support In the following the OpenSCENARIO attributes are listed with their current support status. #### General OpenSCENARIO setup This covers all part that are defined outside the OpenSCENARIO Storyboard
Attribute Support Notes
FileHeader Use "CARLA:" at the beginning of the description to use the CARLA coordinate system.
CatalogLocations
ControllerCatalog
While the catalog is supported, the reference/usage may not work.
CatalogLocations
EnvironmentCatalog
CatalogLocations
ManeuverCatalog
CatalogLocations
MiscObjectCatalog
CatalogLocations
PedestrianCatalog
CatalogLocations
RouteCatalog
While the catalog is supported, the reference/usage may not work.
CatalogLocations
TrajectoryCatalog
While the catalog is supported, the reference/usage may not work.
CatalogLocations
VehicleCatalog
ParameterDeclarations
RoadNetwork
LogicFile
The CARLA level can be used directly (e.g. LogicFile=Town01). Also any OpenDRIVE path can be provided.
RoadNetwork
SceneGraphFile
The provided information is not used.
RoadNetwork
TafficSignals
The provided information is not used.
Entities
EntitySelection
The provided information is not used.
EntitiesScenarioObject
CatalogReference
The provided information is not used.
EntitiesScenarioObject
MiscObject
The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. BoundingBox entries are ignored.
EntitiesScenarioObject
ObjectController
The provided information is not used.
EntitiesScenarioObject
Pedestrian
The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. BoundingBox entries are ignored.
EntitiesScenarioObject
Vehicle
The name should match a CARLA vehicle model, otherwise a default vehicle based on the vehicleCategory is used. The color can be set via properties ('Property name="color" value="0,0,255"'). Axles, Performance, BoundingBox entries are ignored.

#### OpenSCENARIO Storyboard ##### OpenSCENARIO Actions The OpenSCENARIO Actions can be used for two different purposes. First, Actions can be used to define the initial behavior of something, e.g. a traffic participant. Therefore, Actions can be used within the OpenSCENARIO Init. In addition, Actions are also used within the OpenSCENARIO story. In the following, the support status for both application areas is listed. If an action contains of submodules, which are not listed, the support status applies to all submodules. ###### GlobalAction
GlobalAction Init
support
Story
support
Notes
EntityAction
EnvironmentAction
ParameterAction
InfrastructureActionTrafficSignalAction
TrafficAction
InfrastructureActionTrafficSignalAction
TrafficSignalControllerAction
InfrastructureActionTrafficSignalAction
TrafficSignalStateAction
As traffic signals in CARLA towns have no unique ID, they have to be set by providing their position (Example: TrafficSignalStateAction name="pos=x,y" state="green"). The id can also be used for none CARLA town (Example: TrafficSignalStateAction name="id=n" state="green")

###### UserDefinedAction
UserDefinedAction Init
support
Story
support
Notes
CustomCommandAction This action is currently used to trigger the execution of an additional script. Example: type="python /path/to/script args".

###### PrivateAction
PrivateAction Init
support
Story
support
Notes
ActivateControllerAction Can be used to activate/deactive the CARLA autopilot.
ControllerAction AssignControllerAction is supported, but a Python module has to be provided for the controller implementation, and in OverrideControllerValueAction all values need to be False.
LateralAction
LaneChangeAction
Currently only lane change by one lane to the left or right is supported (RelativeTargetLane).
LateralAction
LaneOffsetAction
LateralAction
LateralDistanceAction
LongitudinalAction
LongitudinalDistanceAction
LongitudinalAction
SpeedAction
SynchronizeAction
TeleportAction
VisibilityAction
RoutingAction
AcquirePositionAction
RoutingAction
AssignRouteAction
RoutingAction
FollowTrajectoryAction

##### OpenSCENARIO Conditions Conditions in OpenSCENARIO can be defined either as ByEntityCondition or as ByValueCondition. Both can be used for StartTrigger and StopTrigger conditions. The following two tables list the support status for each. ###### ByEntityCondition
EntityCondition Support Notes
AccelerationCondition
CollisionCondition
DistanceCondition *freespace* attribute is still not supported
EndOfRoadCondition
OffroadCondition
ReachPositionCondition
RelativeDistanceCondition *freespace* attribute is still not supported
RelativeSpeedCondition
SpeedCondition
StandStillCondition
TimeHeadwayCondition *freespace* attribute is still not supported
TimeToCollisionCondition *freespace* attribute is still not supported
TraveledDistanceCondition

###### ByValueCondition
ValueCondition Support Notes
ParameterCondition The level of support depends on the parameter. It is recommended to use other conditions if possible. Please also consider the note below.
SimulationTimeCondition
StoryboardElementStateCondition startTransition, stopTransition, endTransition and completeState are currently supported.
TimeOfDayCondition
TrafficSignalCondition As traffic signals in CARLA towns have no unique ID, they have to be set by providing their position (Example: TrafficSignalCondition name="pos=x,y" state="green"). The id can also be used for none CARLA town (Example: TrafficSignalCondition name="id=n" state="green")
TrafficSignalControllerCondition
UserDefinedValueCondition

!!! Note In the OpenSCENARIO 1.0 standard, a definition of test / evaluation criteria is not defined. For this purpose, you can re-use StopTrigger conditions with CARLA. The following StopTrigger conditions for evaluation criteria are supported through ParameterConditions by providing the criteria name for the condition: * criteria_RunningStopTest * criteria_RunningRedLightTest * criteria_WrongLaneTest * criteria_OnSideWalkTest * criteria_KeepLaneTest * criteria_CollisionTest * criteria_DrivenDistanceTest ##### OpenSCENARIO Positions There are several ways of defining positions in OpenSCENARIO. In the following we list the current support status for each definition format.
Position Support Notes
LanePosition
RelativeLanePosition
RelativeObjectPosition
RelativeRoadPosition
RelativeWorldPosition
RoadPosition
RoutePosition
WorldPosition

================================================ FILE: scenario_runner/Docs/requirements.txt ================================================ mkdocs >= 1.0 markdown-include mkdocs-redirects ================================================ FILE: scenario_runner/Docs/ros_agent.md ================================================ # ROS-based Challenge Agent Interfacing CARLA from ROS is normally done via [CARLA ROS Bridge](https://github.com/carla-simulator/ros-bridge). In Challenge Mode this bridging functionality is provided by a RosAgent. It uses the same topics and message-types for the sensors but does not publish tf-transformations. # Requirements * `roscore` is expected to be running in the docker container. Please adapt your entrypoint. ## Setup To enable your stack within challenge mode, the following steps need to be taken: 1. Define Sensor Setup 2. Define Startup ### Define Sensor Setup Derive from RosAgent and implement the sensors() method. from srunner.autoagents.ros_agent import RosAgent class MyRosAgent(RosAgent): def sensors(self): return [ ] As an example for the sensor definition, see [HumanAgent.py](../srunner/autoagents/human_agent.py). ### Define Startup The startup of the stack is done within the shell script `$TEAM_CODE_ROOT/start.sh`. Therefore the environment variable `TEAM_CODE_ROOT` must be set. RosAgent takes care of executing and monitoring. The script shall remain running as long as the stack is active. Example for start.sh #!/bin/bash -e roslaunch $TEAM_CODE_ROOT/challenge.launch ## Testing In general, the challenge execution is headless. For diagnosis you're still able to use ros-tools like rviz or rqt. Additionally you can use [carla_manual_control](https://github.com/carla-simulator/ros-bridge/tree/master/carla_manual_control) from the carla_ros_bridge for visualization (and also controlling the vehicle). ================================================ FILE: scenario_runner/Jenkinsfile ================================================ #!/usr/bin/env groovy String CARLA_HOST String CARLA_RELEASE String TEST_HOST String COMMIT String ECR_REPOSITORY = "456841689987.dkr.ecr.eu-west-3.amazonaws.com/scenario_runner" boolean CARLA_RUNNING = false boolean CONCURRENCY = true // V3 - include detection of concurrent builds pipeline { agent none options { buildDiscarder(logRotator(numToKeepStr: '3', artifactNumToKeepStr: '3')) skipDefaultCheckout() } stages { stage('setup') { agent { label "master" } steps { checkout scm script { jenkinsLib = load("/home/jenkins/scenario_runner.groovy") TEST_HOST = jenkinsLib.getUbuntuTestNodeHost() CARLA_HOST= sh( script: "cat ./CARLA_VER | grep HOST | sed 's/HOST\\s*=\\s*//g'", returnStdout: true).trim() CARLA_RELEASE = sh( script: "cat ./CARLA_VER | grep RELEASE | sed 's/RELEASE\\s*=\\s*//g'", returnStdout: true).trim() COMMIT = sh(returnStdout: true, script: "git log -n 1 --pretty=format:'%h'").trim() } println "using CARLA version ${CARLA_RELEASE} from ${TEST_HOST}" } } stage('get concurrency status') { options { lock resource: 'ubuntu_gpu', skipIfLocked: true } agent { label "master" } steps { script { CONCURRENCY = false println "no concurrent builds detected." } } } stage('act on concurrency') { agent { label "master" } steps { script { if ( CONCURRENCY == true ) { println "concurrent builds detected, prebuilding SR image." stage('prebuild SR docker image') { //checkout scm sh "docker build -t jenkins/scenario_runner:${COMMIT} ." sh "docker tag jenkins/scenario_runner:${COMMIT} ${ECR_REPOSITORY}:${COMMIT}" sh '$(aws ecr get-login | sed \'s/ -e none//g\' )' sh "docker push ${ECR_REPOSITORY}" sh "docker image rmi -f \"\$(docker images -q ${ECR_REPOSITORY}:${COMMIT})\"" } } } } } stage('lock ubuntu_gpu instance') { options { lock resource: "ubuntu_gpu" } stages { stage('start server') { agent { label "master" } steps { script { jenkinsLib = load("/home/jenkins/scenario_runner.groovy") jenkinsLib.StartUbuntuTestNode() } } } stage('deploy') { parallel { stage('build SR docker image') { agent { label "master" } steps { script { if ( CONCURRENCY == false ) { //checkout scm sh "docker build -t jenkins/scenario_runner:${COMMIT} ." sh "docker tag jenkins/scenario_runner:${COMMIT} ${ECR_REPOSITORY}:${COMMIT}" sh '$(aws ecr get-login | sed \'s/ -e none//g\' )' sh "docker push ${ECR_REPOSITORY}" sh "docker image rmi -f \"\$(docker images -q ${ECR_REPOSITORY}:${COMMIT})\"" } else { println "SR docker image already built due concurrency" } } } } stage('deploy CARLA') { stages { stage('install CARLA') { agent { label "secondary && ubuntu && gpu && sr" } steps { println "using CARLA version ${CARLA_RELEASE}" sh "wget -qO- ${CARLA_HOST}/${CARLA_RELEASE}.tar.gz | tar -xzv -C ." } } } } } } stage('run test') { agent { label "secondary && ubuntu && gpu && sr" } steps { sh 'DISPLAY= ./CarlaUE4.sh -opengl -nosound > CarlaUE4.log&' sleep 10 script { sh '$(aws ecr get-login | sed \'s/ -e none//g\' )' sh "docker pull ${ECR_REPOSITORY}:${COMMIT}" sh "docker container run --rm --network host -e LANG=C.UTF-8 \"${ECR_REPOSITORY}:${COMMIT}\" -c \"python3 scenario_runner.py --scenario FollowLeadingVehicle_1 --debug --output --reloadWorld \"" deleteDir() } } } } post { always { node('master') { script { jenkinsLib = load("/home/jenkins/scenario_runner.groovy") jenkinsLib.StopUbuntuTestNode() echo 'test node stopped' sh 'docker system prune --volumes -f' } deleteDir() } } } } } } ================================================ FILE: scenario_runner/LICENSE ================================================ MIT License Copyright (c) 2018 CARLA 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. ================================================ FILE: scenario_runner/README.md ================================================ ## Note by ThinkTwice We have changed/added some log related functions of the srunner for easier debug. For example, each simulated route would have a index in its folder name. For all infractions, the location and timestep would be recorded in the json file. Original README.md ======================== [![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](https://opensource.org/licenses/MIT) ![GitHub tag (latest SemVer)](https://img.shields.io/github/tag/carla-simulator/scenario_runner.svg) [![Build Status](https://travis-ci.com/carla-simulator/scenario_runner.svg?branch=master)](https://travis-ci.com/carla/scenario_runner) ScenarioRunner for CARLA ======================== This repository contains traffic scenario definition and an execution engine for CARLA. It also allows the execution of a simulation of the CARLA Challenge. You can use this system to prepare your agent for the CARLA Challenge. Scenarios can be defined through a Python interface, and with the newest version the scenario_runner also the upcoming [OpenSCENARIO](http://www.openscenario.org/) standard is supported. [![Scenario_Runner for CARLA](Docs/img/scenario_runner_video.png)](https://youtu.be/ChmF8IFagpo?t=68) Getting the ScenarioRunner --------------------------- Use `git clone` or download the project from this page. Note that the master branch contains the latest fixes and features, and may be required to use the latest features from CARLA. It is important to also consider the release version that has to match the CARLA version. * [Version 0.9.10](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.10) and the 0.9.10 Branch: Compatible with [CARLA 0.9.10](https://github.com/carla-simulator/carla/releases/tag/0.9.10) * [Version 0.9.9](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.9) and the 0.9.9 Branch: Compatible with [CARLA 0.9.9](https://github.com/carla-simulator/carla/releases/tag/0.9.9). Use the 0.9.9 branch, if you use CARLA 0.9.9.4. * [Version 0.9.8](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.8) and the 0.9.8 Branch: Compatible with [CARLA 0.9.8](https://github.com/carla-simulator/carla/releases/tag/0.9.8) * [Version 0.9.7](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.7) and the 0.9.7 Branch: Compatible with [CARLA 0.9.7](https://github.com/carla-simulator/carla/releases/tag/0.9.7) but not with the later release patch versions. * [Version 0.9.6](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.6) and the 0.9.6 Branch: Compatible with [CARLA 0.9.6](https://github.com/carla-simulator/carla/releases/tag/0.9.6) * [Version 0.9.5](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.5) and [Version 0.9.5.1](https://github.com/carla-simulator/scenario_runner/releases/tag/v0.9.5.1): Compatible with [CARLA 0.9.5](https://github.com/carla-simulator/carla/releases/tag/0.9.5) * [Version 0.9.2](https://github.com/carla-simulator/scenario_runner/releases/tag/0.9.2): Compatible with [CARLA 0.9.2](https://github.com/carla-simulator/carla/releases/tag/0.9.2) To use a particular version you can either download the corresponding tarball or simply checkout the version tag associated to the release (e.g. git checkout v0.9.5) Currently no build is required, as all code is in Python. Using the ScenarioRunner ------------------------ Please take a look at our [Getting started](Docs/getting_scenariorunner.md) documentation. Challenge Evaluation --------------------- You can evaluate your own agents using a reproduction of the CARLA Challenge by following [this tutorial](Docs/challenge_evaluation.md) Contributing ------------ Please take a look at our [Contribution guidelines](https://carla.readthedocs.io/en/latest/#contributing). FAQ ------ If you run into problems, check our [FAQ](http://carla.readthedocs.io/en/latest/faq/). License ------- ScenarioRunner specific code is distributed under MIT License. ================================================ FILE: scenario_runner/manual_control.py ================================================ #!/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 . # Allows controlling a vehicle with a keyboard. For a simpler and more # documented example, please take a look at tutorial.py. """ Welcome to CARLA manual control. Use ARROWS or WASD keys for control. W : throttle S : brake A/D : steer left/right Q : toggle reverse Space : hand-brake P : toggle autopilot M : toggle manual transmission ,/. : gear up/down L : toggle next light type SHIFT + L : toggle high beam Z/X : toggle right/left blinker I : toggle interior light TAB : change sensor position ` or N : next sensor [1-9] : change to sensor [1-9] G : toggle radar visualization C : change weather (Shift+C reverse) R : toggle recording images to disk CTRL + R : toggle recording of simulation (replacing any previous) CTRL + P : start replaying last recorded simulation CTRL + + : increments the start time of the replay by 1 second (+SHIFT = 10 seconds) CTRL + - : decrements the start time of the replay by 1 second (+SHIFT = 10 seconds) F1 : toggle HUD H/? : toggle help ESC : quit """ from __future__ import print_function # ============================================================================== # -- imports ------------------------------------------------------------------- # ============================================================================== import carla from examples.manual_control import (World, HUD, KeyboardControl, CameraManager, CollisionSensor, LaneInvasionSensor, GnssSensor, IMUSensor) import os import argparse import logging import time import pygame # ============================================================================== # -- Global functions ---------------------------------------------------------- # ============================================================================== def get_actor_display_name(actor, truncate=250): name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:]) return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name # ============================================================================== # -- World --------------------------------------------------------------------- # ============================================================================== class WorldSR(World): restarted = False def restart(self): if self.restarted: return self.restarted = True self.player_max_speed = 1.589 self.player_max_speed_fast = 3.713 # Keep same camera config if the camera manager exists. cam_index = self.camera_manager.index if self.camera_manager is not None else 0 cam_pos_index = self.camera_manager.transform_index if self.camera_manager is not None else 0 # Get the ego vehicle while self.player is None: print("Waiting for the ego vehicle...") time.sleep(1) possible_vehicles = self.world.get_actors().filter('vehicle.*') for vehicle in possible_vehicles: if vehicle.attributes['role_name'] == "hero": print("Ego vehicle found") self.player = vehicle break self.player_name = self.player.type_id # Set up the sensors. self.collision_sensor = CollisionSensor(self.player, self.hud) self.lane_invasion_sensor = LaneInvasionSensor(self.player, self.hud) self.gnss_sensor = GnssSensor(self.player) self.imu_sensor = IMUSensor(self.player) self.camera_manager = CameraManager(self.player, self.hud, self._gamma) self.camera_manager.transform_index = cam_pos_index self.camera_manager.set_sensor(cam_index, notify=False) actor_type = get_actor_display_name(self.player) self.hud.notification(actor_type) def tick(self, clock): if len(self.world.get_actors().filter(self.player_name)) < 1: return False self.hud.tick(self, clock) return True # ============================================================================== # -- game_loop() --------------------------------------------------------------- # ============================================================================== def game_loop(args): pygame.init() pygame.font.init() world = None try: client = carla.Client(args.host, args.port) client.set_timeout(2.0) display = pygame.display.set_mode( (args.width, args.height), pygame.HWSURFACE | pygame.DOUBLEBUF) hud = HUD(args.width, args.height) world = WorldSR(client.get_world(), hud, args) controller = KeyboardControl(world, args.autopilot) clock = pygame.time.Clock() while True: clock.tick_busy_loop(60) if controller.parse_events(client, world, clock): return if not world.tick(clock): return world.render(display) pygame.display.flip() finally: if (world and world.recording_enabled): client.stop_recorder() if world is not None: world.destroy() pygame.quit() # ============================================================================== # -- main() -------------------------------------------------------------------- # ============================================================================== def main(): argparser = argparse.ArgumentParser( description='CARLA Manual Control Client') argparser.add_argument( '-v', '--verbose', action='store_true', dest='debug', help='print debug information') 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( '-a', '--autopilot', action='store_true', help='enable autopilot') argparser.add_argument( '--res', metavar='WIDTHxHEIGHT', default='1280x720', help='window resolution (default: 1280x720)') args = argparser.parse_args() args.rolename = 'hero' # Needed for CARLA version args.filter = "vehicle.*" # Needed for CARLA version args.gamma = 2.2 # Needed for CARLA version args.width, args.height = [int(x) for x in args.res.split('x')] log_level = logging.DEBUG if args.debug else logging.INFO logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level) logging.info('listening to server %s:%s', args.host, args.port) print(__doc__) try: game_loop(args) except KeyboardInterrupt: print('\nCancelled by user. Bye!') except Exception as error: logging.exception(error) if __name__ == '__main__': main() ================================================ FILE: scenario_runner/metrics_manager.py ================================================ #!/usr/bin/env python # 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 . # Allows the execution of user-implemented metrics """ Welcome to the ScenarioRunner's metric module This is the main script to be executed when running a metric. It is responsible of parsing all the information and executing the metric specified by the user. """ import os import sys import importlib import inspect import json import argparse from argparse import RawTextHelpFormatter import carla from srunner.metrics.tools.metrics_log import MetricsLog class MetricsManager(object): """ Main class of the metrics module. Handles the parsing and execution of the metrics. """ def __init__(self, args): """ Initialization of the metrics manager. This creates the client, needed to parse the information from the recorder, extract the metrics class, and runs it """ self._args = args # Parse the arguments recorder_str = self._get_recorder(self._args.log) criteria_dict = self._get_criteria(self._args.criteria) # Get the correct world and load it map_name = self._get_recorder_map(recorder_str) world = self._client.load_world(map_name) town_map = world.get_map() # Instanciate the MetricsLog, used to querry the needed information log = MetricsLog(recorder_str) # Read and run the metric class metric_class = self._get_metric_class(self._args.metric) metric_class(town_map, log, criteria_dict) def _get_recorder(self, log): """ Parses the log argument into readable information """ # Get the log information. self._client = carla.Client(self._args.host, self._args.port) recorder_file = "{}/{}".format(os.getenv('SCENARIO_RUNNER_ROOT', "./"), log) # Check that the file is correct if recorder_file[-4:] != '.log': print("ERROR: The log argument has to point to a .log file") sys.exit(-1) if not os.path.exists(recorder_file): print("ERROR: The specified log file does not exist") sys.exit(-1) recorder_str = self._client.show_recorder_file_info(recorder_file, True) return recorder_str def _get_criteria(self, criteria_file): """ Parses the criteria argument into a dictionary """ if criteria_file: with open(criteria_file) as fd: criteria_dict = json.load(fd) else: criteria_dict = None return criteria_dict def _get_metric_class(self, metric_file): """ Function to extract the metrics class from the path given by the metrics argument. Returns the first class found that is a child of BasicMetric Args: metric_file (str): path to the metric's file. """ # Get their module module_name = os.path.basename(metric_file).split('.')[0] sys.path.insert(0, os.path.dirname(metric_file)) metric_module = importlib.import_module(module_name) # And their members of type class for member in inspect.getmembers(metric_module, inspect.isclass): # Get the first one with parent BasicMetrics member_parent = member[1].__bases__[0] if 'BasicMetric' in str(member_parent): return member[1] print("No child class of BasicMetric was found ... Exiting") sys.exit(-1) def _get_recorder_map(self, recorder_str): """ Returns the name of the map the simulation took place in """ header = recorder_str.split("\n") sim_map = header[1][5:] return sim_map def main(): """ main function """ # pylint: disable=line-too-long description = ("Scenario Runner's metrics module. Evaluate the execution of a specific scenario by developing your own metric.\n") parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter) parser.add_argument('--host', default='127.0.0.1', help='IP of the host server (default: localhost)') parser.add_argument('--port', '-p', default=2000, help='TCP port to listen to (default: 2000)') parser.add_argument('--log', required=True, help='Path to the CARLA recorder .log file (relative to SCENARIO_RUNNER_ROOT).\nThis file is created by the record functionality at ScenarioRunner') parser.add_argument('--metric', required=True, help='Path to the .py file defining the used metric.\nSome examples at srunner/metrics') parser.add_argument('--criteria', default="", help='Path to the .json file with the criteria information.\nThis file is created by the record functionality at ScenarioRunner') # pylint: enable=line-too-long args = parser.parse_args() MetricsManager(args) if __name__ == "__main__": sys.exit(main()) ================================================ FILE: scenario_runner/mkdocs.yml ================================================ site_name: CARLA ScenarioRunner repo_url: https://github.com/carla-simulator/scenario_runner docs_dir: Docs edit_uri: 'edit/master/Docs/' theme: readthedocs extra_css: [extra.css] nav: - Home: index.md - Quick start: - Get ScenarioRunner: getting_scenariorunner.md - First steps: getting_started.md - Create a new scenario: creating_new_scenario.md - Metrics module: metrics_module.md - FAQ: FAQ.md - Release Notes: CHANGELOG.md - References: - List of scenarios: list_of_scenarios.md - OpenSCENARIO support: openscenario_support.md - Contributing: - Code of conduct: CODE_OF_CONDUCT.md - Coding standard: coding_standard.md - Contribution guidelines: CONTRIBUTING.md markdown_extensions: - admonition - markdown_include.include: base_path: '.' ================================================ FILE: scenario_runner/no_rendering_mode.py ================================================ #!/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 . # Allows visualising a 2D map generated by vehicles. """ Welcome to CARLA No-Rendering Mode Visualizer TAB : toggle hero mode Mouse Wheel : zoom in / zoom out Mouse Drag : move map (map mode only) W : throttle S : brake AD : steer Q : toggle reverse Space : hand-brake P : toggle autopilot M : toggle manual transmission ,/. : gear up/down F1 : toggle HUD I : toggle actor ids H/? : toggle help ESC : quit """ # ============================================================================== # -- find carla module --------------------------------------------------------- # ============================================================================== 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 # ============================================================================== # -- imports ------------------------------------------------------------------- # ============================================================================== import carla from carla import TrafficLightState as tls import argparse import logging import datetime import weakref import math import random try: import pygame from pygame.locals import KMOD_CTRL from pygame.locals import KMOD_SHIFT from pygame.locals import K_COMMA from pygame.locals import K_DOWN from pygame.locals import K_ESCAPE from pygame.locals import K_F1 from pygame.locals import K_LEFT from pygame.locals import K_PERIOD from pygame.locals import K_RIGHT from pygame.locals import K_SLASH from pygame.locals import K_SPACE from pygame.locals import K_TAB from pygame.locals import K_UP from pygame.locals import K_a from pygame.locals import K_d from pygame.locals import K_h from pygame.locals import K_i from pygame.locals import K_m from pygame.locals import K_p from pygame.locals import K_q from pygame.locals import K_s from pygame.locals import K_w except ImportError: raise RuntimeError('cannot import pygame, make sure pygame package is installed') # ============================================================================== # -- Constants ----------------------------------------------------------------- # ============================================================================== # Colors # We will use the color palette used in Tango Desktop Project (Each color is indexed depending on brightness level) # See: https://en.wikipedia.org/wiki/Tango_Desktop_Project COLOR_BUTTER_0 = pygame.Color(252, 233, 79) COLOR_BUTTER_1 = pygame.Color(237, 212, 0) COLOR_BUTTER_2 = pygame.Color(196, 160, 0) COLOR_ORANGE_0 = pygame.Color(252, 175, 62) COLOR_ORANGE_1 = pygame.Color(245, 121, 0) COLOR_ORANGE_2 = pygame.Color(209, 92, 0) COLOR_CHOCOLATE_0 = pygame.Color(233, 185, 110) COLOR_CHOCOLATE_1 = pygame.Color(193, 125, 17) COLOR_CHOCOLATE_2 = pygame.Color(143, 89, 2) COLOR_CHAMELEON_0 = pygame.Color(138, 226, 52) COLOR_CHAMELEON_1 = pygame.Color(115, 210, 22) COLOR_CHAMELEON_2 = pygame.Color(78, 154, 6) COLOR_SKY_BLUE_0 = pygame.Color(114, 159, 207) COLOR_SKY_BLUE_1 = pygame.Color(52, 101, 164) COLOR_SKY_BLUE_2 = pygame.Color(32, 74, 135) COLOR_PLUM_0 = pygame.Color(173, 127, 168) COLOR_PLUM_1 = pygame.Color(117, 80, 123) COLOR_PLUM_2 = pygame.Color(92, 53, 102) COLOR_SCARLET_RED_0 = pygame.Color(239, 41, 41) COLOR_SCARLET_RED_1 = pygame.Color(204, 0, 0) COLOR_SCARLET_RED_2 = pygame.Color(164, 0, 0) COLOR_ALUMINIUM_0 = pygame.Color(238, 238, 236) COLOR_ALUMINIUM_1 = pygame.Color(211, 215, 207) COLOR_ALUMINIUM_2 = pygame.Color(186, 189, 182) COLOR_ALUMINIUM_3 = pygame.Color(136, 138, 133) COLOR_ALUMINIUM_4 = pygame.Color(85, 87, 83) COLOR_ALUMINIUM_4_5 = pygame.Color(66, 62, 64) COLOR_ALUMINIUM_5 = pygame.Color(46, 52, 54) COLOR_WHITE = pygame.Color(255, 255, 255) COLOR_BLACK = pygame.Color(0, 0, 0) # Module Defines MODULE_WORLD = 'WORLD' MODULE_HUD = 'HUD' MODULE_INPUT = 'INPUT' PIXELS_PER_METER = 12 MAP_DEFAULT_SCALE = 0.1 HERO_DEFAULT_SCALE = 1.0 PIXELS_AHEAD_VEHICLE = 150 # ============================================================================== # -- Util ----------------------------------------------------------- # ============================================================================== def get_actor_display_name(actor, truncate=250): name = ' '.join(actor.type_id.replace('_', '.').title().split('.')[1:]) return (name[:truncate - 1] + u'\u2026') if len(name) > truncate else name class Util(object): @staticmethod def blits(destination_surface, source_surfaces, rect=None, blend_mode=0): for surface in source_surfaces: destination_surface.blit(surface[0], surface[1], rect, blend_mode) @staticmethod def length(v): return math.sqrt(v.x**2 + v.y**2 + v.z**2) @staticmethod def get_bounding_box(actor): bb = actor.trigger_volume.extent corners = [carla.Location(x=-bb.x, y=-bb.y), carla.Location(x=bb.x, y=-bb.y), carla.Location(x=bb.x, y=bb.y), carla.Location(x=-bb.x, y=bb.y), carla.Location(x=-bb.x, y=-bb.y)] corners = [x + actor.trigger_volume.location for x in corners] t = actor.get_transform() t.transform(corners) return corners # ============================================================================== # -- ModuleManager ------------------------------------------------------------- # ============================================================================== class ModuleManager(object): def __init__(self): self.modules = [] def register_module(self, module): self.modules.append(module) def clear_modules(self): del self.modules[:] def tick(self, clock): # Update all the modules for module in self.modules: module.tick(clock) def render(self, display): display.fill(COLOR_ALUMINIUM_4) for module in self.modules: module.render(display) def get_module(self, name): for module in self.modules: if module.name == name: return module def start_modules(self): for module in self.modules: module.start() # ============================================================================== # -- FadingText ---------------------------------------------------------------- # ============================================================================== class FadingText(object): def __init__(self, font, dim, pos): self.font = font self.dim = dim self.pos = pos self.seconds_left = 0 self.surface = pygame.Surface(self.dim) def set_text(self, text, color=COLOR_WHITE, seconds=2.0): text_texture = self.font.render(text, True, color) self.surface = pygame.Surface(self.dim) self.seconds_left = seconds self.surface.fill(COLOR_BLACK) self.surface.blit(text_texture, (10, 11)) def tick(self, clock): delta_seconds = 1e-3 * clock.get_time() self.seconds_left = max(0.0, self.seconds_left - delta_seconds) self.surface.set_alpha(500.0 * self.seconds_left) def render(self, display): display.blit(self.surface, self.pos) # ============================================================================== # -- HelpText ------------------------------------------------------------------ # ============================================================================== class HelpText(object): def __init__(self, font, width, height): lines = __doc__.split('\n') self.font = font self.dim = (680, len(lines) * 22 + 12) self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1]) self.seconds_left = 0 self.surface = pygame.Surface(self.dim) self.surface.fill(COLOR_BLACK) for n, line in enumerate(lines): text_texture = self.font.render(line, True, COLOR_WHITE) self.surface.blit(text_texture, (22, n * 22)) self._render = False self.surface.set_alpha(220) def toggle(self): self._render = not self._render def render(self, display): if self._render: display.blit(self.surface, self.pos) # ============================================================================== # -- ModuleHUD ----------------------------------------------------------------- # ============================================================================== class ModuleHUD (object): def __init__(self, name, width, height): self.name = name self.dim = (width, height) self._init_hud_params() self._init_data_params() def start(self): pass def _init_hud_params(self): fonts = [x for x in pygame.font.get_fonts() if 'mono' in x] default_font = 'ubuntumono' mono = default_font if default_font in fonts else fonts[0] mono = pygame.font.match_font(mono) self._font_mono = pygame.font.Font(mono, 14) self._header_font = pygame.font.SysFont('Arial', 14, True) self.help = HelpText(pygame.font.Font(mono, 24), *self.dim) self._notifications = FadingText( pygame.font.Font(pygame.font.get_default_font(), 20), (self.dim[0], 40), (0, self.dim[1] - 40)) def _init_data_params(self): self.show_info = True self.show_actor_ids = False self._info_text = {} def notification(self, text, seconds=2.0): self._notifications.set_text(text, seconds=seconds) def tick(self, clock): self._notifications.tick(clock) def add_info(self, module_name, info): self._info_text[module_name] = info def render_vehicles_ids(self, vehicle_id_surface, list_actors, world_to_pixel, hero_actor, hero_transform): vehicle_id_surface.fill(COLOR_BLACK) if self.show_actor_ids: vehicle_id_surface.set_alpha(150) for actor in list_actors: x, y = world_to_pixel(actor[1].location) angle = 0 if hero_actor is not None: angle = -hero_transform.rotation.yaw - 90 color = COLOR_SKY_BLUE_0 if int(actor[0].attributes['number_of_wheels']) == 2: color = COLOR_CHOCOLATE_0 if actor[0].attributes['role_name'] == 'hero': color = COLOR_CHAMELEON_0 font_surface = self._header_font.render(str(actor[0].id), True, color) rotated_font_surface = pygame.transform.rotate(font_surface, angle) rect = rotated_font_surface.get_rect(center=(x, y)) vehicle_id_surface.blit(rotated_font_surface, rect) return vehicle_id_surface def render(self, display): if self.show_info: info_surface = pygame.Surface((240, self.dim[1])) info_surface.set_alpha(100) display.blit(info_surface, (0, 0)) v_offset = 4 bar_h_offset = 100 bar_width = 106 i = 0 for module_name, module_info in self._info_text.items(): if not module_info: continue surface = self._header_font.render(module_name, True, COLOR_ALUMINIUM_0).convert_alpha() display.blit(surface, (8 + bar_width / 2, 18 * i + v_offset)) v_offset += 12 i += 1 for item in module_info: if v_offset + 18 > self.dim[1]: break if isinstance(item, list): if len(item) > 1: points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item)] pygame.draw.lines(display, (255, 136, 0), False, points, 2) item = None elif isinstance(item, tuple): if isinstance(item[1], bool): rect = pygame.Rect((bar_h_offset, v_offset + 8), (6, 6)) pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect, 0 if item[1] else 1) else: rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6)) pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect_border, 1) f = (item[1] - item[2]) / (item[3] - item[2]) if item[2] < 0.0: rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6)) else: rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6)) pygame.draw.rect(display, COLOR_ALUMINIUM_0, rect) item = item[0] if item: # At this point has to be a str. surface = self._font_mono.render(item, True, COLOR_ALUMINIUM_0).convert_alpha() display.blit(surface, (8, 18 * i + v_offset)) v_offset += 18 v_offset += 24 self._notifications.render(display) self.help.render(display) # ============================================================================== # -- TrafficLightSurfaces ------------------------------------------------------ # ============================================================================== class TrafficLightSurfaces(object): """Holds the surfaces (scaled and rotated) for painting traffic lights""" def __init__(self): def make_surface(tl): w = 40 surface = pygame.Surface((w, 3 * w), pygame.SRCALPHA) surface.fill(COLOR_ALUMINIUM_5 if tl != 'h' else COLOR_ORANGE_2) if tl != 'h': hw = int(w / 2) off = COLOR_ALUMINIUM_4 red = COLOR_SCARLET_RED_0 yellow = COLOR_BUTTER_0 green = COLOR_CHAMELEON_0 pygame.draw.circle(surface, red if tl == tls.Red else off, (hw, hw), int(0.4 * w)) pygame.draw.circle(surface, yellow if tl == tls.Yellow else off, (hw, w + hw), int(0.4 * w)) pygame.draw.circle(surface, green if tl == tls.Green else off, (hw, 2 * w + hw), int(0.4 * w)) return pygame.transform.smoothscale(surface, (15, 45) if tl != 'h' else (19, 49)) self._original_surfaces = { 'h': make_surface('h'), tls.Red: make_surface(tls.Red), tls.Yellow: make_surface(tls.Yellow), tls.Green: make_surface(tls.Green), tls.Off: make_surface(tls.Off), tls.Unknown: make_surface(tls.Unknown) } self.surfaces = dict(self._original_surfaces) def rotozoom(self, angle, scale): for key, surface in self._original_surfaces.items(): self.surfaces[key] = pygame.transform.rotozoom(surface, angle, scale) # ============================================================================== # -- World --------------------------------------------------------------------- # ============================================================================== class MapImage(object): def __init__(self, carla_world, carla_map, pixels_per_meter, show_triggers, show_connections, show_spawn_points): self._pixels_per_meter = pixels_per_meter self.scale = 1.0 self.show_triggers = show_triggers self.show_connections = show_connections self.show_spawn_points = show_spawn_points waypoints = carla_map.generate_waypoints(2) margin = 50 max_x = max(waypoints, key=lambda x: x.transform.location.x).transform.location.x + margin max_y = max(waypoints, key=lambda x: x.transform.location.y).transform.location.y + margin min_x = min(waypoints, key=lambda x: x.transform.location.x).transform.location.x - margin min_y = min(waypoints, key=lambda x: x.transform.location.y).transform.location.y - margin self.width = max(max_x - min_x, max_y - min_y) self._world_offset = (min_x, min_y) width_in_pixels = int(self._pixels_per_meter * self.width) self.big_map_surface = pygame.Surface((width_in_pixels, width_in_pixels)).convert() self.draw_road_map(self.big_map_surface, carla_world, carla_map, self.world_to_pixel, self.world_to_pixel_width) self.surface = self.big_map_surface def draw_road_map(self, map_surface, carla_world, carla_map, world_to_pixel, world_to_pixel_width): map_surface.fill(COLOR_ALUMINIUM_4) precision = 0.05 def lane_marking_color_to_tango(lane_marking_color): tango_color = COLOR_BLACK if lane_marking_color == carla.LaneMarkingColor.White: tango_color = COLOR_ALUMINIUM_2 elif lane_marking_color == carla.LaneMarkingColor.Blue: tango_color = COLOR_SKY_BLUE_0 elif lane_marking_color == carla.LaneMarkingColor.Green: tango_color = COLOR_CHAMELEON_0 elif lane_marking_color == carla.LaneMarkingColor.Red: tango_color = COLOR_SCARLET_RED_0 elif lane_marking_color == carla.LaneMarkingColor.Yellow: tango_color = COLOR_ORANGE_0 return tango_color def draw_solid_line(surface, color, closed, points, width): if len(points) >= 2: pygame.draw.lines(surface, color, closed, points, width) def draw_broken_line(surface, color, closed, points, width): broken_lines = [x for n, x in enumerate(zip(*(iter(points),) * 20)) if n % 3 == 0] for line in broken_lines: pygame.draw.lines(surface, color, closed, line, width) def get_lane_markings(lane_marking_type, lane_marking_color, waypoints, sign): margin = 0.20 if lane_marking_type == carla.LaneMarkingType.Broken or (lane_marking_type == carla.LaneMarkingType.Solid): marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints] return [(lane_marking_type, lane_marking_color, marking_1)] elif lane_marking_type == carla.LaneMarkingType.SolidBroken or lane_marking_type == carla.LaneMarkingType.BrokenSolid: marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints] marking_2 = [world_to_pixel(lateral_shift(w.transform, sign * (w.lane_width * 0.5 + margin * 2))) for w in waypoints] return [(carla.LaneMarkingType.Solid, lane_marking_color, marking_1), (carla.LaneMarkingType.Broken, lane_marking_color, marking_2)] elif lane_marking_type == carla.LaneMarkingType.BrokenBroken: marking = [world_to_pixel(lateral_shift(w.transform, sign * (w.lane_width * 0.5 - margin))) for w in waypoints] return [(carla.LaneMarkingType.Broken, lane_marking_color, marking)] elif lane_marking_type == carla.LaneMarkingType.SolidSolid: marking = [world_to_pixel(lateral_shift(w.transform, sign * ((w.lane_width * 0.5) - margin))) for w in waypoints] return [(carla.LaneMarkingType.Solid, lane_marking_color, marking)] return [(carla.LaneMarkingType.NONE, carla.LaneMarkingColor.Other, [])] def draw_lane_marking(surface, waypoints, is_left): sign = -1 if is_left else 1 lane_marking = None marking_type = carla.LaneMarkingType.NONE previous_marking_type = carla.LaneMarkingType.NONE marking_color = carla.LaneMarkingColor.Other previous_marking_color = carla.LaneMarkingColor.Other waypoints_list = [] temp_waypoints = [] current_lane_marking = carla.LaneMarkingType.NONE for sample in waypoints: lane_marking = sample.left_lane_marking if sign < 0 else sample.right_lane_marking if lane_marking is None: continue marking_type = lane_marking.type marking_color = lane_marking.color if current_lane_marking != marking_type: markings = get_lane_markings( previous_marking_type, lane_marking_color_to_tango(previous_marking_color), temp_waypoints, sign) current_lane_marking = marking_type for marking in markings: waypoints_list.append(marking) temp_waypoints = temp_waypoints[-1:] else: temp_waypoints.append((sample)) previous_marking_type = marking_type previous_marking_color = marking_color # Add last marking last_markings = get_lane_markings( previous_marking_type, lane_marking_color_to_tango(previous_marking_color), temp_waypoints, sign) for marking in last_markings: waypoints_list.append(marking) for markings in waypoints_list: if markings[0] == carla.LaneMarkingType.Solid: draw_solid_line(surface, markings[1], False, markings[2], 2) elif markings[0] == carla.LaneMarkingType.Broken: draw_broken_line(surface, markings[1], False, markings[2], 2) def draw_arrow(surface, transform, color=COLOR_ALUMINIUM_2): transform.rotation.yaw += 180 forward = transform.get_forward_vector() transform.rotation.yaw += 90 right_dir = transform.get_forward_vector() end = transform.location start = end - 2.0 * forward right = start + 0.8 * forward + 0.4 * right_dir left = start + 0.8 * forward - 0.4 * right_dir pygame.draw.lines( surface, color, False, [ world_to_pixel(x) for x in [ start, end]], 4) pygame.draw.lines( surface, color, False, [ world_to_pixel(x) for x in [ left, start, right]], 4) def draw_traffic_signs(surface, font_surface, actor, color=COLOR_ALUMINIUM_2, trigger_color=COLOR_PLUM_0): transform = actor.get_transform() waypoint = carla_map.get_waypoint(transform.location) angle = -waypoint.transform.rotation.yaw - 90.0 font_surface = pygame.transform.rotate(font_surface, angle) pixel_pos = world_to_pixel(waypoint.transform.location) offset = font_surface.get_rect(center=(pixel_pos[0], pixel_pos[1])) surface.blit(font_surface, offset) # Draw line in front of stop forward_vector = carla.Location(waypoint.transform.get_forward_vector()) left_vector = carla.Location(-forward_vector.y, forward_vector.x, forward_vector.z) * waypoint.lane_width / 2 * 0.7 line = [(waypoint.transform.location + (forward_vector * 1.5) + (left_vector)), (waypoint.transform.location + (forward_vector * 1.5) - (left_vector))] line_pixel = [world_to_pixel(p) for p in line] pygame.draw.lines(surface, color, True, line_pixel, 2) # draw bounding box if self.show_triggers: corners = Util.get_bounding_box(actor) corners = [world_to_pixel(p) for p in corners] pygame.draw.lines(surface, trigger_color, True, corners, 2) def lateral_shift(transform, shift): transform.rotation.yaw += 90 return transform.location + shift * transform.get_forward_vector() def draw_topology(carla_topology, index): topology = [x[index] for x in carla_topology] topology = sorted(topology, key=lambda w: w.transform.location.z) for waypoint in topology: # if waypoint.road_id == 150 or waypoint.road_id == 16: waypoints = [waypoint] nxt = waypoint.next(precision) if len(nxt) > 0: nxt = nxt[0] while nxt.road_id == waypoint.road_id: waypoints.append(nxt) nxt = nxt.next(precision) if len(nxt) > 0: nxt = nxt[0] else: break # Draw Road road_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in waypoints] road_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in waypoints] polygon = road_left_side + [x for x in reversed(road_right_side)] polygon = [world_to_pixel(x) for x in polygon] if len(polygon) > 2: pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon, 5) pygame.draw.polygon(map_surface, COLOR_ALUMINIUM_5, polygon) # Draw Shoulders and Parkings PARKING_COLOR = COLOR_ALUMINIUM_4_5 SHOULDER_COLOR = COLOR_ALUMINIUM_5 final_color = SHOULDER_COLOR # Draw Right shoulder = [] for w in waypoints: r = w.get_right_lane() if r is not None and ( r.lane_type == carla.LaneType.Shoulder or r.lane_type == carla.LaneType.Parking): if r.lane_type == carla.LaneType.Parking: final_color = PARKING_COLOR shoulder.append(r) shoulder_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in shoulder] shoulder_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in shoulder] polygon = shoulder_left_side + [x for x in reversed(shoulder_right_side)] polygon = [world_to_pixel(x) for x in polygon] if len(polygon) > 2: pygame.draw.polygon(map_surface, final_color, polygon, 5) pygame.draw.polygon(map_surface, final_color, polygon) draw_lane_marking( map_surface, shoulder, False) # Draw Left shoulder = [] for w in waypoints: r = w.get_left_lane() if r is not None and ( r.lane_type == carla.LaneType.Shoulder or r.lane_type == carla.LaneType.Parking): if r.lane_type == carla.LaneType.Parking: final_color = PARKING_COLOR shoulder.append(r) shoulder_left_side = [lateral_shift(w.transform, -w.lane_width * 0.5) for w in shoulder] shoulder_right_side = [lateral_shift(w.transform, w.lane_width * 0.5) for w in shoulder] polygon = shoulder_left_side + [x for x in reversed(shoulder_right_side)] polygon = [world_to_pixel(x) for x in polygon] if len(polygon) > 2: pygame.draw.polygon(map_surface, final_color, polygon, 5) pygame.draw.polygon(map_surface, final_color, polygon) draw_lane_marking( map_surface, shoulder, True) # Draw Lane Markings and Arrows if not waypoint.is_intersection: draw_lane_marking( map_surface, waypoints, True) draw_lane_marking( map_surface, waypoints, False) for n, wp in enumerate(waypoints): if ((n + 1) % 400) == 0: draw_arrow(map_surface, wp.transform) topology = carla_map.get_topology() draw_topology(topology, 0) draw_topology(topology, 1) if self.show_spawn_points: for sp in carla_map.get_spawn_points(): draw_arrow(map_surface, sp, color=COLOR_CHOCOLATE_0) if self.show_connections: dist = 1.5 to_pixel = lambda wp: world_to_pixel(wp.transform.location) for wp in carla_map.generate_waypoints(dist): col = (0, 255, 255) if wp.is_intersection else (0, 255, 0) for nxt in wp.next(dist): pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(nxt), 2) if wp.lane_change & carla.LaneChange.Right: r = wp.get_right_lane() if r and r.lane_type == carla.LaneType.Driving: pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(r), 2) if wp.lane_change & carla.LaneChange.Left: l = wp.get_left_lane() if l and l.lane_type == carla.LaneType.Driving: pygame.draw.line(map_surface, col, to_pixel(wp), to_pixel(l), 2) actors = carla_world.get_actors() # Draw Traffic Signs font_size = world_to_pixel_width(1) font = pygame.font.SysFont('Arial', font_size, True) stops = [actor for actor in actors if 'stop' in actor.type_id] yields = [actor for actor in actors if 'yield' in actor.type_id] stop_font_surface = font.render("STOP", False, COLOR_ALUMINIUM_2) stop_font_surface = pygame.transform.scale( stop_font_surface, (stop_font_surface.get_width(), stop_font_surface.get_height() * 2)) yield_font_surface = font.render("YIELD", False, COLOR_ALUMINIUM_2) yield_font_surface = pygame.transform.scale( yield_font_surface, (yield_font_surface.get_width(), yield_font_surface.get_height() * 2)) for ts_stop in stops: draw_traffic_signs(map_surface, stop_font_surface, ts_stop, trigger_color=COLOR_SCARLET_RED_1) for ts_yield in yields: draw_traffic_signs(map_surface, yield_font_surface, ts_yield, trigger_color=COLOR_ORANGE_1) def world_to_pixel(self, location, offset=(0, 0)): x = self.scale * self._pixels_per_meter * (location.x - self._world_offset[0]) y = self.scale * self._pixels_per_meter * (location.y - self._world_offset[1]) return [int(x - offset[0]), int(y - offset[1])] def world_to_pixel_width(self, width): return int(self.scale * self._pixels_per_meter * width) def scale_map(self, scale): if scale != self.scale: self.scale = scale width = int(self.big_map_surface.get_width() * self.scale) self.surface = pygame.transform.smoothscale(self.big_map_surface, (width, width)) class ModuleWorld(object): def __init__(self, name, args, timeout): self.client = None self.name = name self.args = args self.timeout = timeout self.server_fps = 0.0 self.simulation_time = 0 self.server_clock = pygame.time.Clock() # World data self.world = None self.town_map = None self.actors_with_transforms = [] # Store necessary modules self.module_hud = None self.module_input = None self.surface_size = [0, 0] self.prev_scaled_size = 0 self.scaled_size = 0 # Hero actor self.hero_actor = None self.spawned_hero = None self.hero_transform = None self.scale_offset = [0, 0] self.vehicle_id_surface = None self.result_surface = None self.traffic_light_surfaces = TrafficLightSurfaces() self.affected_traffic_light = None # Map info self.map_image = None self.border_round_surface = None self.original_surface_size = None self.hero_surface = None self.actors_surface = None def _get_data_from_carla(self): try: self.client = carla.Client(self.args.host, self.args.port) self.client.set_timeout(self.timeout) if self.args.map is None: world = self.client.get_world() else: world = self.client.load_world(self.args.map) town_map = world.get_map() return (world, town_map) except RuntimeError as ex: logging.error(ex) exit_game() def start(self): self.world, self.town_map = self._get_data_from_carla() # Create Surfaces self.map_image = MapImage( carla_world=self.world, carla_map=self.town_map, pixels_per_meter=PIXELS_PER_METER, show_triggers=self.args.show_triggers, show_connections=self.args.show_connections, show_spawn_points=self.args.show_spawn_points) # Store necessary modules self.module_hud = module_manager.get_module(MODULE_HUD) self.module_input = module_manager.get_module(MODULE_INPUT) self.original_surface_size = min(self.module_hud.dim[0], self.module_hud.dim[1]) self.surface_size = self.map_image.big_map_surface.get_width() self.scaled_size = int(self.surface_size) self.prev_scaled_size = int(self.surface_size) # Render Actors self.actors_surface = pygame.Surface((self.map_image.surface.get_width(), self.map_image.surface.get_height())) self.actors_surface.set_colorkey(COLOR_BLACK) self.vehicle_id_surface = pygame.Surface((self.surface_size, self.surface_size)).convert() self.vehicle_id_surface.set_colorkey(COLOR_BLACK) self.border_round_surface = pygame.Surface(self.module_hud.dim, pygame.SRCALPHA).convert() self.border_round_surface.set_colorkey(COLOR_WHITE) self.border_round_surface.fill(COLOR_BLACK) center_offset = (int(self.module_hud.dim[0] / 2), int(self.module_hud.dim[1] / 2)) pygame.draw.circle(self.border_round_surface, COLOR_ALUMINIUM_1, center_offset, int(self.module_hud.dim[1] / 2)) pygame.draw.circle(self.border_round_surface, COLOR_WHITE, center_offset, int((self.module_hud.dim[1] - 8) / 2)) scaled_original_size = self.original_surface_size * (1.0 / 0.9) self.hero_surface = pygame.Surface((scaled_original_size, scaled_original_size)).convert() self.result_surface = pygame.Surface((self.surface_size, self.surface_size)).convert() self.result_surface.set_colorkey(COLOR_BLACK) # Start hero mode by default self.select_hero_actor() self.hero_actor.set_autopilot(False) self.module_input.wheel_offset = HERO_DEFAULT_SCALE self.module_input.control = carla.VehicleControl() weak_self = weakref.ref(self) self.world.on_tick(lambda timestamp: ModuleWorld.on_world_tick(weak_self, timestamp)) def select_hero_actor(self): hero_vehicles = [actor for actor in self.world.get_actors( ) if 'vehicle' in actor.type_id and actor.attributes['role_name'] == 'hero'] if len(hero_vehicles) > 0: self.hero_actor = random.choice(hero_vehicles) self.hero_transform = self.hero_actor.get_transform() else: self._spawn_hero() def _spawn_hero(self): # Get a random blueprint. blueprint = random.choice(self.world.get_blueprint_library().filter(self.args.filter)) blueprint.set_attribute('role_name', 'hero') if blueprint.has_attribute('color'): color = random.choice(blueprint.get_attribute('color').recommended_values) blueprint.set_attribute('color', color) # Spawn the player. while self.hero_actor is None: spawn_points = self.world.get_map().get_spawn_points() spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform() self.hero_actor = self.world.try_spawn_actor(blueprint, spawn_point) self.hero_transform = self.hero_actor.get_transform() # Save it in order to destroy it when closing program self.spawned_hero = self.hero_actor def tick(self, clock): actors = self.world.get_actors() self.actors_with_transforms = [(actor, actor.get_transform()) for actor in actors] if self.hero_actor is not None: self.hero_transform = self.hero_actor.get_transform() self.update_hud_info(clock) def update_hud_info(self, clock): hero_mode_text = [] if self.hero_actor is not None: hero_speed = self.hero_actor.get_velocity() hero_speed_text = 3.6 * math.sqrt(hero_speed.x ** 2 + hero_speed.y ** 2 + hero_speed.z ** 2) affected_traffic_light_text = 'None' if self.affected_traffic_light is not None: state = self.affected_traffic_light.state if state == carla.TrafficLightState.Green: affected_traffic_light_text = 'GREEN' elif state == carla.TrafficLightState.Yellow: affected_traffic_light_text = 'YELLOW' else: affected_traffic_light_text = 'RED' affected_speed_limit_text = self.hero_actor.get_speed_limit() hero_mode_text = [ 'Hero Mode: ON', 'Hero ID: %7d' % self.hero_actor.id, 'Hero Vehicle: %14s' % get_actor_display_name(self.hero_actor, truncate=14), 'Hero Speed: %3d km/h' % hero_speed_text, 'Hero Affected by:', ' Traffic Light: %12s' % affected_traffic_light_text, ' Speed Limit: %3d km/h' % affected_speed_limit_text ] else: hero_mode_text = ['Hero Mode: OFF'] self.server_fps = self.server_clock.get_fps() self.server_fps = 'inf' if self.server_fps == float('inf') else round(self.server_fps) module_info_text = [ 'Server: % 16s FPS' % self.server_fps, 'Client: % 16s FPS' % round(clock.get_fps()), 'Simulation Time: % 12s' % datetime.timedelta(seconds=int(self.simulation_time)), 'Map Name: %10s' % self.town_map.name, ] module_info_text = module_info_text module_hud = module_manager.get_module(MODULE_HUD) module_hud.add_info(self.name, module_info_text) module_hud.add_info('HERO', hero_mode_text) @staticmethod def on_world_tick(weak_self, timestamp): self = weak_self() if not self: return self.server_clock.tick() self.server_fps = self.server_clock.get_fps() self.simulation_time = timestamp.elapsed_seconds def _split_actors(self): vehicles = [] traffic_lights = [] speed_limits = [] walkers = [] for actor_with_transform in self.actors_with_transforms: actor = actor_with_transform[0] if 'vehicle' in actor.type_id: vehicles.append(actor_with_transform) elif 'traffic_light' in actor.type_id: traffic_lights.append(actor_with_transform) elif 'speed_limit' in actor.type_id: speed_limits.append(actor_with_transform) elif 'walker' in actor.type_id: walkers.append(actor_with_transform) info_text = [] if self.hero_actor is not None and len(vehicles) > 1: location = self.hero_transform.location vehicle_list = [x[0] for x in vehicles if x[0].id != self.hero_actor.id] def distance(v): return location.distance(v.get_location()) for n, vehicle in enumerate(sorted(vehicle_list, key=distance)): if n > 15: break vehicle_type = get_actor_display_name(vehicle, truncate=22) info_text.append('% 5d %s' % (vehicle.id, vehicle_type)) module_manager.get_module(MODULE_HUD).add_info( 'NEARBY VEHICLES', info_text) return (vehicles, traffic_lights, speed_limits, walkers) def _render_traffic_lights(self, surface, list_tl, world_to_pixel): self.affected_traffic_light = None for tl in list_tl: world_pos = tl.get_location() pos = world_to_pixel(world_pos) if self.args.show_triggers: corners = Util.get_bounding_box(tl) corners = [world_to_pixel(p) for p in corners] pygame.draw.lines(surface, COLOR_BUTTER_1, True, corners, 2) if self.hero_actor is not None: corners = Util.get_bounding_box(tl) corners = [world_to_pixel(p) for p in corners] tl_t = tl.get_transform() transformed_tv = tl_t.transform(tl.trigger_volume.location) hero_location = self.hero_actor.get_location() d = hero_location.distance(transformed_tv) s = Util.length(tl.trigger_volume.extent) + Util.length(self.hero_actor.bounding_box.extent) if (d <= s): # Highlight traffic light self.affected_traffic_light = tl srf = self.traffic_light_surfaces.surfaces['h'] surface.blit(srf, srf.get_rect(center=pos)) srf = self.traffic_light_surfaces.surfaces[tl.state] surface.blit(srf, srf.get_rect(center=pos)) def _render_speed_limits(self, surface, list_sl, world_to_pixel, world_to_pixel_width): font_size = world_to_pixel_width(2) radius = world_to_pixel_width(2) font = pygame.font.SysFont('Arial', font_size) for sl in list_sl: x, y = world_to_pixel(sl.get_location()) # Render speed limit white_circle_radius = int(radius * 0.75) pygame.draw.circle(surface, COLOR_SCARLET_RED_1, (x, y), radius) pygame.draw.circle(surface, COLOR_ALUMINIUM_0, (x, y), white_circle_radius) limit = sl.type_id.split('.')[2] font_surface = font.render(limit, True, COLOR_ALUMINIUM_5) if self.args.show_triggers: corners = Util.get_bounding_box(sl) corners = [world_to_pixel(p) for p in corners] pygame.draw.lines(surface, COLOR_PLUM_2, True, corners, 2) # Blit if self.hero_actor is not None: # Rotate font surface with respect to hero vehicle front angle = -self.hero_transform.rotation.yaw - 90.0 font_surface = pygame.transform.rotate(font_surface, angle) offset = font_surface.get_rect(center=(x, y)) surface.blit(font_surface, offset) else: surface.blit(font_surface, (x - radius / 2, y - radius / 2)) def _render_walkers(self, surface, list_w, world_to_pixel): for w in list_w: color = COLOR_PLUM_0 # Compute bounding box points bb = w[0].bounding_box.extent corners = [ carla.Location(x=-bb.x, y=-bb.y), carla.Location(x=bb.x, y=-bb.y), carla.Location(x=bb.x, y=bb.y), carla.Location(x=-bb.x, y=bb.y)] w[1].transform(corners) corners = [world_to_pixel(p) for p in corners] pygame.draw.polygon(surface, color, corners) def _render_vehicles(self, surface, list_v, world_to_pixel): for v in list_v: color = COLOR_SKY_BLUE_0 if int(v[0].attributes['number_of_wheels']) == 2: color = COLOR_CHOCOLATE_1 if v[0].attributes['role_name'] == 'hero': color = COLOR_CHAMELEON_0 # Compute bounding box points bb = v[0].bounding_box.extent corners = [carla.Location(x=-bb.x, y=-bb.y), carla.Location(x=bb.x - 0.8, y=-bb.y), carla.Location(x=bb.x, y=0), carla.Location(x=bb.x - 0.8, y=bb.y), carla.Location(x=-bb.x, y=bb.y), carla.Location(x=-bb.x, y=-bb.y) ] v[1].transform(corners) corners = [world_to_pixel(p) for p in corners] pygame.draw.lines(surface, color, False, corners, int(math.ceil(4.0 * self.map_image.scale))) def render_actors(self, surface, vehicles, traffic_lights, speed_limits, walkers): # Static actors self._render_traffic_lights(surface, [tl[0] for tl in traffic_lights], self.map_image.world_to_pixel) self._render_speed_limits(surface, [sl[0] for sl in speed_limits], self.map_image.world_to_pixel, self.map_image.world_to_pixel_width) # Dynamic actors self._render_vehicles(surface, vehicles, self.map_image.world_to_pixel) self._render_walkers(surface, walkers, self.map_image.world_to_pixel) def clip_surfaces(self, clipping_rect): self.actors_surface.set_clip(clipping_rect) self.vehicle_id_surface.set_clip(clipping_rect) self.result_surface.set_clip(clipping_rect) def _compute_scale(self, scale_factor): m = self.module_input.mouse_pos # Percentage of surface where mouse position is actually px = (m[0] - self.scale_offset[0]) / float(self.prev_scaled_size) py = (m[1] - self.scale_offset[1]) / float(self.prev_scaled_size) # Offset will be the previously accumulated offset added with the # difference of mouse positions in the old and new scales diff_between_scales = ((float(self.prev_scaled_size) * px) - (float(self.scaled_size) * px), (float(self.prev_scaled_size) * py) - (float(self.scaled_size) * py)) self.scale_offset = (self.scale_offset[0] + diff_between_scales[0], self.scale_offset[1] + diff_between_scales[1]) # Update previous scale self.prev_scaled_size = self.scaled_size # Scale performed self.map_image.scale_map(scale_factor) def render(self, display): if self.actors_with_transforms is None: return self.result_surface.fill(COLOR_BLACK) vehicles, traffic_lights, speed_limits, walkers = self._split_actors() scale_factor = self.module_input.wheel_offset self.scaled_size = int(self.map_image.width * scale_factor) if self.scaled_size != self.prev_scaled_size: self._compute_scale(scale_factor) # Render Actors self.actors_surface.fill(COLOR_BLACK) self.render_actors( self.actors_surface, vehicles, traffic_lights, speed_limits, walkers) # Render Ids self.module_hud.render_vehicles_ids(self.vehicle_id_surface, vehicles, self.map_image.world_to_pixel, self.hero_actor, self.hero_transform) # Blit surfaces surfaces = ((self.map_image.surface, (0, 0)), (self.actors_surface, (0, 0)), (self.vehicle_id_surface, (0, 0)), ) angle = 0.0 if self.hero_actor is None else self.hero_transform.rotation.yaw + 90.0 self.traffic_light_surfaces.rotozoom(-angle, self.map_image.scale) center_offset = (0, 0) if self.hero_actor is not None: hero_location_screen = self.map_image.world_to_pixel(self.hero_transform.location) hero_front = self.hero_transform.get_forward_vector() translation_offset = ( hero_location_screen[0] - self.hero_surface.get_width() / 2 + hero_front.x * PIXELS_AHEAD_VEHICLE, (hero_location_screen[1] - self.hero_surface.get_height() / 2 + hero_front.y * PIXELS_AHEAD_VEHICLE)) # Apply clipping rect clipping_rect = pygame.Rect(translation_offset[0], translation_offset[1], self.hero_surface.get_width(), self.hero_surface.get_height()) self.clip_surfaces(clipping_rect) Util.blits(self.result_surface, surfaces) self.border_round_surface.set_clip(clipping_rect) self.hero_surface.fill(COLOR_ALUMINIUM_4) self.hero_surface.blit(self.result_surface, (-translation_offset[0], -translation_offset[1])) rotated_result_surface = pygame.transform.rotozoom(self.hero_surface, angle, 0.9).convert() center = (display.get_width() / 2, display.get_height() / 2) rotation_pivot = rotated_result_surface.get_rect(center=center) display.blit(rotated_result_surface, rotation_pivot) display.blit(self.border_round_surface, (0, 0)) else: # Translation offset translation_offset = (self.module_input.mouse_offset[0] * scale_factor + self.scale_offset[0], self.module_input.mouse_offset[1] * scale_factor + self.scale_offset[1]) center_offset = (abs(display.get_width() - self.surface_size) / 2 * scale_factor, 0) # Apply clipping rect clipping_rect = pygame.Rect(-translation_offset[0] - center_offset[0], -translation_offset[1], self.module_hud.dim[0], self.module_hud.dim[1]) self.clip_surfaces(clipping_rect) Util.blits(self.result_surface, surfaces) display.blit(self.result_surface, (translation_offset[0] + center_offset[0], translation_offset[1])) def destroy(self): if self.spawned_hero is not None: self.spawned_hero.destroy() # ============================================================================== # -- Input ----------------------------------------------------------- # ============================================================================== class ModuleInput(object): def __init__(self, name): self.name = name self.mouse_pos = (0, 0) self.mouse_offset = [0.0, 0.0] self.wheel_offset = 0.1 self.wheel_amount = 0.025 self._steer_cache = 0.0 self.control = None self._autopilot_enabled = False def start(self): hud = module_manager.get_module(MODULE_HUD) hud.notification("Press 'H' or '?' for help.", seconds=4.0) def render(self, display): pass def tick(self, clock): self.parse_input(clock) def _parse_events(self): self.mouse_pos = pygame.mouse.get_pos() for event in pygame.event.get(): if event.type == pygame.QUIT: exit_game() elif event.type == pygame.KEYUP: if self._is_quit_shortcut(event.key): exit_game() elif event.key == K_h or (event.key == K_SLASH and pygame.key.get_mods() & KMOD_SHIFT): module_hud = module_manager.get_module(MODULE_HUD) module_hud.help.toggle() elif event.key == K_TAB: module_world = module_manager.get_module(MODULE_WORLD) module_hud = module_manager.get_module(MODULE_HUD) if module_world.hero_actor is None: module_world.select_hero_actor() self.wheel_offset = HERO_DEFAULT_SCALE self.control = carla.VehicleControl() module_hud.notification('Hero Mode') else: self.wheel_offset = MAP_DEFAULT_SCALE self.mouse_offset = [0, 0] self.mouse_pos = [0, 0] module_world.scale_offset = [0, 0] module_world.hero_actor = None module_hud.notification('Map Mode') elif event.key == K_F1: module_hud = module_manager.get_module(MODULE_HUD) module_hud.show_info = not module_hud.show_info elif event.key == K_i: module_hud = module_manager.get_module(MODULE_HUD) module_hud.show_actor_ids = not module_hud.show_actor_ids elif isinstance(self.control, carla.VehicleControl): if event.key == K_q: self.control.gear = 1 if self.control.reverse else -1 elif event.key == K_m: self.control.manual_gear_shift = not self.control.manual_gear_shift world = module_manager.get_module(MODULE_WORLD) self.control.gear = world.hero_actor.get_control().gear module_hud = module_manager.get_module(MODULE_HUD) module_hud.notification('%s Transmission' % ( 'Manual' if self.control.manual_gear_shift else 'Automatic')) elif self.control.manual_gear_shift and event.key == K_COMMA: self.control.gear = max(-1, self.control.gear - 1) elif self.control.manual_gear_shift and event.key == K_PERIOD: self.control.gear = self.control.gear + 1 elif event.key == K_p: world = module_manager.get_module(MODULE_WORLD) if world.hero_actor is not None: self._autopilot_enabled = not self._autopilot_enabled world.hero_actor.set_autopilot(self._autopilot_enabled) module_hud = module_manager.get_module(MODULE_HUD) module_hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off')) elif event.type == pygame.MOUSEBUTTONDOWN: if event.button == 4: self.wheel_offset += self.wheel_amount if self.wheel_offset >= 1.0: self.wheel_offset = 1.0 elif event.button == 5: self.wheel_offset -= self.wheel_amount if self.wheel_offset <= 0.1: self.wheel_offset = 0.1 def _parse_keys(self, milliseconds): keys = pygame.key.get_pressed() self.control.throttle = 1.0 if keys[K_UP] or keys[K_w] else 0.0 steer_increment = 5e-4 * milliseconds if keys[K_LEFT] or keys[K_a]: self._steer_cache -= steer_increment elif keys[K_RIGHT] or keys[K_d]: self._steer_cache += steer_increment else: self._steer_cache = 0.0 self._steer_cache = min(0.7, max(-0.7, self._steer_cache)) self.control.steer = round(self._steer_cache, 1) self.control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0 self.control.hand_brake = keys[K_SPACE] def _parse_mouse(self): if pygame.mouse.get_pressed()[0]: x, y = pygame.mouse.get_pos() self.mouse_offset[0] += (1.0 / self.wheel_offset) * (x - self.mouse_pos[0]) self.mouse_offset[1] += (1.0 / self.wheel_offset) * (y - self.mouse_pos[1]) self.mouse_pos = (x, y) def parse_input(self, clock): self._parse_events() self._parse_mouse() if not self._autopilot_enabled: if isinstance(self.control, carla.VehicleControl): self._parse_keys(clock.get_time()) self.control.reverse = self.control.gear < 0 world = module_manager.get_module(MODULE_WORLD) if (world.hero_actor is not None): world.hero_actor.apply_control(self.control) @staticmethod def _is_quit_shortcut(key): return (key == K_ESCAPE) or (key == K_q and pygame.key.get_mods() & KMOD_CTRL) # ============================================================================== # -- Global Objects ------------------------------------------------------------ # ============================================================================== module_manager = ModuleManager() # ============================================================================== # -- Game Loop --------------------------------------------------------------- # ============================================================================== def game_loop(args): try: # Init Pygame pygame.init() display = pygame.display.set_mode( (args.width, args.height), pygame.HWSURFACE | pygame.DOUBLEBUF) pygame.display.set_caption(args.description) font = pygame.font.Font(pygame.font.get_default_font(), 20) text_surface = font.render('Rendering map...', True, COLOR_WHITE) display.blit(text_surface, text_surface.get_rect(center=(args.width / 2, args.height / 2))) pygame.display.flip() # Init modules input_module = ModuleInput(MODULE_INPUT) hud_module = ModuleHUD(MODULE_HUD, args.width, args.height) world_module = ModuleWorld(MODULE_WORLD, args, timeout=2.0) # Register Modules module_manager.register_module(world_module) module_manager.register_module(hud_module) module_manager.register_module(input_module) module_manager.start_modules() clock = pygame.time.Clock() while True: clock.tick_busy_loop(60) module_manager.tick(clock) module_manager.render(display) pygame.display.flip() except KeyboardInterrupt: print('\nCancelled by user. Bye!') finally: if world_module is not None: world_module.destroy() def exit_game(): module_manager.clear_modules() pygame.quit() sys.exit() # ============================================================================== # -- Main -------------------------------------------------------------------- # ============================================================================== def main(): # Parse arguments argparser = argparse.ArgumentParser( description='CARLA No Rendering Mode Visualizer') argparser.add_argument( '-v', '--verbose', action='store_true', dest='debug', help='print debug information') 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( '--res', metavar='WIDTHxHEIGHT', default='1280x720', help='window resolution (default: 1280x720)') argparser.add_argument( '--filter', metavar='PATTERN', default='vehicle.*', help='actor filter (default: "vehicle.*")') argparser.add_argument( '--map', metavar='TOWN', default=None, help='start a new episode at the given TOWN') argparser.add_argument( '--no-rendering', action='store_true', default=True, help='switch off server rendering') argparser.add_argument( '--show-triggers', action='store_true', help='show trigger boxes of traffic signs') argparser.add_argument( '--show-connections', action='store_true', help='show waypoint connections') argparser.add_argument( '--show-spawn-points', action='store_true', help='show recommended spawn points') args = argparser.parse_args() args.description = argparser.description args.width, args.height = [int(x) for x in args.res.split('x')] log_level = logging.DEBUG if args.debug else logging.INFO logging.basicConfig(format='%(levelname)s: %(message)s', level=log_level) logging.info('listening to server %s:%s', args.host, args.port) print(__doc__) game_loop(args) if __name__ == '__main__': main() ================================================ FILE: scenario_runner/requirements.txt ================================================ py-trees==0.8.3 networkx==2.2 Shapely==1.6.4.post2 psutil xmlschema==1.0.18 carla ephem tabulate opencv-python==4.2.0.32 numpy matplotlib six ================================================ FILE: scenario_runner/scenario_runner.py ================================================ #!/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.scenarioconfigs.openscenario_configuration import OpenScenarioConfiguration from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenario_manager import ScenarioManager from srunner.scenarios.open_scenario import OpenScenario from srunner.scenarios.route_scenario import RouteScenario from srunner.tools.scenario_parser import ScenarioConfigurationParser from srunner.tools.route_parser import RouteParser # Version of scenario_runner VERSION = '0.9.9' 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 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.8'): raise ImportError("CARLA version 0.9.8 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() self._cleanup() if not self.manager.get_running_status(): raise RuntimeError("Timeout occured during scenario execution") 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 """ # Simulation still running and in synchronous mode? if self.manager is not None and self.manager.get_running_status() \ and self.world is not None and self._args.sync: # Reset to asynchronous mode settings = self.world.get_settings() settings.synchronous_mode = False settings.fixed_delta_seconds = None self.world.apply_settings(settings) self.manager.cleanup() CarlaDataProvider.cleanup() for i, _ in enumerate(self.ego_vehicles): if self.ego_vehicles[i]: if not self._args.waitForEgo: 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 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" filename = None if self._args.file: filename = config_name + current_time + ".txt" if not self.manager.analyze_scenario(self._args.output, filename, junit_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') 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') 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) CarlaDataProvider.set_traffic_manager_port(int(self._args.trafficManagerPort)) # Wait for the world to be ready if CarlaDataProvider.is_sync_mode(): self.world.tick() else: self.world.wait_for_tick() if CarlaDataProvider.get_map().name != town and CarlaDataProvider.get_map().name != "OpenDriveMap": print("The CARLA server uses the wrong map: {}".format(CarlaDataProvider.get_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 # 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) 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): 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 config = OpenScenarioConfiguration(self._args.openscenario, self.client) 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('--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( '--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('--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.route: arguments.reloadWorld = True if arguments.agent: arguments.sync = True scenario_runner = None result = True try: scenario_runner = ScenarioRunner(arguments) result = scenario_runner.run() finally: if scenario_runner is not None: scenario_runner.destroy() del scenario_runner return not result if __name__ == "__main__": sys.exit(main()) ================================================ FILE: scenario_runner/srunner/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/autoagents/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/autoagents/agent_wrapper.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Wrapper for autonomous agents required for tracking and checking of used sensors """ from __future__ import print_function import carla from srunner.autoagents.sensor_interface import CallBack from srunner.scenariomanager.carla_data_provider import CarlaDataProvider class AgentWrapper(object): """ Wrapper for autonomous agents required for tracking and checking of used sensors """ _agent = None _sensors_list = [] def __init__(self, agent): """ Set the autonomous agent """ self._agent = agent def __call__(self): """ Pass the call directly to the agent """ return self._agent() def setup_sensors(self, vehicle, debug_mode=False): """ Create the sensors defined by the user and attach them to the ego-vehicle :param vehicle: ego vehicle :return: """ bp_library = CarlaDataProvider.get_world().get_blueprint_library() for sensor_spec in self._agent.sensors(): # These are the sensors spawned on the carla world bp = bp_library.find(str(sensor_spec['type'])) if sensor_spec['type'].startswith('sensor.camera'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) bp.set_attribute('channels', str(sensor_spec['channels'])) bp.set_attribute('upper_fov', str(sensor_spec['upper_fov'])) bp.set_attribute('lower_fov', str(sensor_spec['lower_fov'])) bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.other.gnss'): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() # create sensor sensor_transform = carla.Transform(sensor_location, sensor_rotation) sensor = CarlaDataProvider.get_world().spawn_actor(bp, sensor_transform, vehicle) # setup callback sensor.listen(CallBack(sensor_spec['id'], sensor, self._agent.sensor_interface)) self._sensors_list.append(sensor) while not self._agent.all_sensors_ready(): if debug_mode: print(" waiting for one data reading from sensors...") CarlaDataProvider.get_world().tick() def cleanup(self): """ Remove and destroy all sensors """ for i, _ in enumerate(self._sensors_list): if self._sensors_list[i] is not None: self._sensors_list[i].stop() self._sensors_list[i].destroy() self._sensors_list[i] = None self._sensors_list = [] ================================================ FILE: scenario_runner/srunner/autoagents/autonomous_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides the base class for all autonomous agents """ from __future__ import print_function import carla from srunner.autoagents.sensor_interface import SensorInterface from srunner.scenariomanager.timer import GameTime from srunner.tools.route_manipulation import downsample_route class AutonomousAgent(object): """ Autonomous agent base class. All user agents have to be derived from this class """ def __init__(self, path_to_conf_file): # current global plans to reach a destination self._global_plan = None self._global_plan_world_coord = None # this data structure will contain all sensor data self.sensor_interface = SensorInterface() # agent's initialization self.setup(path_to_conf_file) def setup(self, path_to_conf_file): """ Initialize everything needed by your agent and set the track attribute to the right type: """ pass def sensors(self): # pylint: disable=no-self-use """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} ] """ sensors = [] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. :return: control """ control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False return control def destroy(self): """ Destroy (clean-up) the agent :return: """ pass def __call__(self): """ Execute the agent call, e.g. agent() Returns the next vehicle controls """ input_data = self.sensor_interface.get_data() timestamp = GameTime.get_time() wallclock = GameTime.get_wallclocktime() print('======[Agent] Wallclock_time = {} / Sim_time = {}'.format(wallclock, timestamp)) control = self.run_step(input_data, timestamp) control.manual_gear_shift = False return control def all_sensors_ready(self): """ Check if all sensors are ready Returns true if sensors are ready """ return self.sensor_interface.all_sensors_ready() def set_global_plan(self, global_plan_gps, global_plan_world_coord): """ Set the plan (route) for the agent """ ds_ids = downsample_route(global_plan_world_coord, 1) self._global_plan_world_coord = [(global_plan_world_coord[x][0], global_plan_world_coord[x][1]) for x in ds_ids] self._global_plan = [global_plan_gps[x] for x in ds_ids] ================================================ FILE: scenario_runner/srunner/autoagents/dummy_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a dummy agent to control the ego vehicle """ from __future__ import print_function import carla from srunner.autoagents.autonomous_agent import AutonomousAgent class DummyAgent(AutonomousAgent): """ Dummy autonomous agent to control the ego vehicle """ def setup(self, path_to_conf_file): """ Setup the agent parameters """ def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} """ sensors = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Center'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0, 'width': 800, 'height': 600, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'id': 'LIDAR'}, {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'}, {'type': 'sensor.can_bus', 'reading_frequency': 25, 'id': 'can_bus'}, {'type': 'sensor.hd_map', 'reading_frequency': 1, 'id': 'hdmap'}, ] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ print("=====================>") for key, val in input_data.items(): if hasattr(val[1], 'shape'): shape = val[1].shape print("[{} -- {:06d}] with shape {}".format(key, val[0], shape)) else: print("[{} -- {:06d}] ".format(key, val[0])) print("<=====================") # DO SOMETHING SMART # RETURN CONTROL control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False return control ================================================ FILE: scenario_runner/srunner/autoagents/human_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a human agent to control the ego vehicle via keyboard """ import time from threading import Thread import cv2 import numpy as np try: import pygame from pygame.locals import K_DOWN from pygame.locals import K_LEFT from pygame.locals import K_RIGHT from pygame.locals import K_SPACE from pygame.locals import K_UP from pygame.locals import K_a from pygame.locals import K_d from pygame.locals import K_s from pygame.locals import K_w except ImportError: raise RuntimeError('cannot import pygame, make sure pygame package is installed') import carla from srunner.autoagents.autonomous_agent import AutonomousAgent class HumanInterface(object): """ Class to control a vehicle manually for debugging purposes """ def __init__(self, parent): self.quit = False self._parent = parent self._width = 800 self._height = 600 self._throttle_delta = 0.05 self._steering_delta = 0.01 self._surface = None pygame.init() pygame.font.init() self._clock = pygame.time.Clock() self._display = pygame.display.set_mode((self._width, self._height), pygame.HWSURFACE | pygame.DOUBLEBUF) pygame.display.set_caption("Human Agent") def run(self): """ Run the GUI """ while not self._parent.agent_engaged and not self.quit: time.sleep(0.5) controller = KeyboardControl() while not self.quit: self._clock.tick_busy_loop(20) controller.parse_events(self._parent.current_control, self._clock) # Process events pygame.event.pump() # process sensor data input_data = self._parent.sensor_interface.get_data() image_center = input_data['Center'][1][:, :, -2::-1] image_left = input_data['Left'][1][:, :, -2::-1] image_right = input_data['Right'][1][:, :, -2::-1] image_rear = input_data['Rear'][1][:, :, -2::-1] top_row = np.hstack((image_left, image_center, image_right)) bottom_row = np.hstack((0 * image_rear, image_rear, 0 * image_rear)) comp_image = np.vstack((top_row, bottom_row)) # resize image image_rescaled = cv2.resize(comp_image, dsize=(self._width, self._height), interpolation=cv2.INTER_CUBIC) # display image self._surface = pygame.surfarray.make_surface(image_rescaled.swapaxes(0, 1)) if self._surface is not None: self._display.blit(self._surface, (0, 0)) pygame.display.flip() pygame.quit() class HumanAgent(AutonomousAgent): """ Human agent to control the ego vehicle via keyboard """ current_control = None agent_engaged = False def setup(self, path_to_conf_file): """ Setup the agent parameters """ self.agent_engaged = False self.current_control = carla.VehicleControl() self.current_control.steer = 0.0 self.current_control.throttle = 1.0 self.current_control.brake = 0.0 self.current_control.hand_brake = False self._hic = HumanInterface(self) self._thread = Thread(target=self._hic.run) self._thread.start() def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ ['sensor.camera.rgb', {'x':x_rel, 'y': y_rel, 'z': z_rel, 'yaw': yaw, 'pitch': pitch, 'roll': roll, 'width': width, 'height': height, 'fov': fov}, 'Sensor01'], ['sensor.camera.rgb', {'x':x_rel, 'y': y_rel, 'z': z_rel, 'yaw': yaw, 'pitch': pitch, 'roll': roll, 'width': width, 'height': height, 'fov': fov}, 'Sensor02'], ['sensor.lidar.ray_cast', {'x':x_rel, 'y': y_rel, 'z': z_rel, 'yaw': yaw, 'pitch': pitch, 'roll': roll}, 'Sensor03'] ] """ sensors = [{'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Center'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': -45.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 45.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.camera.rgb', 'x': -1.8, 'y': 0, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 180.0, 'width': 300, 'height': 200, 'fov': 130, 'id': 'Rear'}, {'type': 'sensor.other.gnss', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'id': 'GPS'} ] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ self.agent_engaged = True time.sleep(0.1) return self.current_control def destroy(self): """ Cleanup """ self._hic.quit = True self._thread.join() class KeyboardControl(object): """ Keyboard control for the human agent """ def __init__(self): """ Init """ self._control = carla.VehicleControl() self._steer_cache = 0.0 def parse_events(self, control, clock): """ Parse the keyboard events and set the vehicle controls accordingly """ for event in pygame.event.get(): if event.type == pygame.QUIT: return self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time()) control.steer = self._control.steer control.throttle = self._control.throttle control.brake = self._control.brake control.hand_brake = self._control.hand_brake def _parse_vehicle_keys(self, keys, milliseconds): """ Calculate new vehicle controls based on input keys """ self._control.throttle = 0.6 if keys[K_UP] or keys[K_w] else 0.0 steer_increment = 15.0 * 5e-4 * milliseconds if keys[K_LEFT] or keys[K_a]: self._steer_cache -= steer_increment elif keys[K_RIGHT] or keys[K_d]: self._steer_cache += steer_increment else: self._steer_cache = 0.0 self._steer_cache = min(0.95, max(-0.95, self._steer_cache)) self._control.steer = round(self._steer_cache, 1) self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0 self._control.hand_brake = keys[K_SPACE] ================================================ FILE: scenario_runner/srunner/autoagents/npc_agent.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an NPC agent to control the ego vehicle """ from __future__ import print_function import carla from agents.navigation.basic_agent import BasicAgent from srunner.autoagents.autonomous_agent import AutonomousAgent from srunner.scenariomanager.carla_data_provider import CarlaDataProvider class NpcAgent(AutonomousAgent): """ NPC autonomous agent to control the ego vehicle """ _agent = None _route_assigned = False def setup(self, path_to_conf_file): """ Setup the agent parameters """ self._route_assigned = False self._agent = None def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors in the following format: [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': 0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Right'}, {'type': 'sensor.lidar.ray_cast', 'x': 0.7, 'y': 0.0, 'z': 1.60, 'yaw': 0.0, 'pitch': 0.0, 'roll': 0.0, 'id': 'LIDAR'} """ sensors = [ {'type': 'sensor.camera.rgb', 'x': 0.7, 'y': -0.4, 'z': 1.60, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, 'width': 300, 'height': 200, 'fov': 100, 'id': 'Left'}, ] return sensors def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ control = carla.VehicleControl() control.steer = 0.0 control.throttle = 0.0 control.brake = 0.0 control.hand_brake = False if not self._agent: hero_actor = None for actor in CarlaDataProvider.get_world().get_actors(): if 'role_name' in actor.attributes and actor.attributes['role_name'] == 'hero': hero_actor = actor break if hero_actor: self._agent = BasicAgent(hero_actor) return control if not self._route_assigned: if self._global_plan: plan = [] for transform, road_option in self._global_plan_world_coord: wp = CarlaDataProvider.get_map().get_waypoint(transform.location) plan.append((wp, road_option)) self._agent._local_planner.set_global_plan(plan) # pylint: disable=protected-access self._route_assigned = True else: control = self._agent.run_step() return control ================================================ FILE: scenario_runner/srunner/autoagents/ros_agent.py ================================================ #!/usr/bin/env python # # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . # """ This module provides a ROS autonomous agent interface to control the ego vehicle via a ROS stack """ import math import os import subprocess import signal import threading import time import numpy import carla import rospy from cv_bridge import CvBridge from geometry_msgs.msg import PoseStamped from nav_msgs.msg import Odometry, Path from rosgraph_msgs.msg import Clock from sensor_msgs.msg import Image, PointCloud2, NavSatFix, NavSatStatus, CameraInfo from sensor_msgs.point_cloud2 import create_cloud_xyz32 from std_msgs.msg import Header, String import tf # pylint: disable=line-too-long from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, CarlaEgoVehicleControl, CarlaWorldInfo # pylint: enable=line-too-long from srunner.autoagents.autonomous_agent import AutonomousAgent class RosAgent(AutonomousAgent): """ Base class for ROS-based stacks. Derive from it and implement the sensors() method. Please define TEAM_CODE_ROOT in your environment. The stack is started by executing $TEAM_CODE_ROOT/start.sh The sensor data is published on similar topics as with the carla-ros-bridge. You can find details about the utilized datatypes there. This agent expects a roscore to be running. """ speed = None current_control = None stack_process = None timestamp = None current_map_name = None step_mode_possible = None vehicle_info_publisher = None global_plan_published = None def setup(self, path_to_conf_file): """ setup agent """ self.stack_thread = None # get start_script from environment team_code_path = os.environ['TEAM_CODE_ROOT'] if not team_code_path or not os.path.exists(team_code_path): raise IOError("Path '{}' defined by TEAM_CODE_ROOT invalid".format(team_code_path)) start_script = "{}/start.sh".format(team_code_path) if not os.path.exists(start_script): raise IOError("File '{}' defined by TEAM_CODE_ROOT invalid".format(start_script)) # set use_sim_time via commandline before init-node process = subprocess.Popen( "rosparam set use_sim_time true", shell=True, stderr=subprocess.STDOUT, stdout=subprocess.PIPE) process.wait() if process.returncode: raise RuntimeError("Could not set use_sim_time") # initialize ros node rospy.init_node('ros_agent', anonymous=True) # publish first clock value '0' self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10, latch=True) self.clock_publisher.publish(Clock(rospy.Time.from_sec(0))) # execute script that starts the ad stack (remains running) rospy.loginfo("Executing stack...") self.stack_process = subprocess.Popen(start_script, shell=True, preexec_fn=os.setpgrp) self.vehicle_control_event = threading.Event() self.timestamp = None self.speed = 0 self.global_plan_published = False self.vehicle_info_publisher = None self.vehicle_status_publisher = None self.odometry_publisher = None self.world_info_publisher = None self.map_file_publisher = None self.current_map_name = None self.tf_broadcaster = None self.step_mode_possible = False self.vehicle_control_subscriber = rospy.Subscriber( '/carla/ego_vehicle/vehicle_control_cmd', CarlaEgoVehicleControl, self.on_vehicle_control) self.current_control = carla.VehicleControl() self.waypoint_publisher = rospy.Publisher( '/carla/ego_vehicle/waypoints', Path, queue_size=1, latch=True) self.publisher_map = {} self.id_to_sensor_type_map = {} self.id_to_camera_info_map = {} self.cv_bridge = CvBridge() # setup ros publishers for sensors # pylint: disable=line-too-long for sensor in self.sensors(): self.id_to_sensor_type_map[sensor['id']] = sensor['type'] if sensor['type'] == 'sensor.camera.rgb': self.publisher_map[sensor['id']] = rospy.Publisher( '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + "/image_color", Image, queue_size=1, latch=True) self.id_to_camera_info_map[sensor['id']] = self.build_camera_info(sensor) self.publisher_map[sensor['id'] + '_info'] = rospy.Publisher( '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + "/camera_info", CameraInfo, queue_size=1, latch=True) elif sensor['type'] == 'sensor.lidar.ray_cast': self.publisher_map[sensor['id']] = rospy.Publisher( '/carla/ego_vehicle/lidar/' + sensor['id'] + "/point_cloud", PointCloud2, queue_size=1, latch=True) elif sensor['type'] == 'sensor.other.gnss': self.publisher_map[sensor['id']] = rospy.Publisher( '/carla/ego_vehicle/gnss/' + sensor['id'] + "/fix", NavSatFix, queue_size=1, latch=True) elif sensor['type'] == 'sensor.can_bus': if not self.vehicle_info_publisher: self.vehicle_info_publisher = rospy.Publisher( '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True) if not self.vehicle_status_publisher: self.vehicle_status_publisher = rospy.Publisher( '/carla/ego_vehicle/vehicle_status', CarlaEgoVehicleStatus, queue_size=1, latch=True) elif sensor['type'] == 'sensor.hd_map': if not self.odometry_publisher: self.odometry_publisher = rospy.Publisher( '/carla/ego_vehicle/odometry', Odometry, queue_size=1, latch=True) if not self.world_info_publisher: self.world_info_publisher = rospy.Publisher( '/carla/world_info', CarlaWorldInfo, queue_size=1, latch=True) if not self.map_file_publisher: self.map_file_publisher = rospy.Publisher('/carla/map_file', String, queue_size=1, latch=True) if not self.tf_broadcaster: self.tf_broadcaster = tf.TransformBroadcaster() else: raise TypeError("Invalid sensor type: {}".format(sensor['type'])) # pylint: enable=line-too-long def destroy(self): """ Cleanup of all ROS publishers """ if self.stack_process and self.stack_process.poll() is None: rospy.loginfo("Sending SIGTERM to stack...") os.killpg(os.getpgid(self.stack_process.pid), signal.SIGTERM) rospy.loginfo("Waiting for termination of stack...") self.stack_process.wait() time.sleep(5) rospy.loginfo("Terminated stack.") rospy.loginfo("Stack is no longer running") self.world_info_publisher.unregister() self.map_file_publisher.unregister() self.vehicle_status_publisher.unregister() self.vehicle_info_publisher.unregister() self.waypoint_publisher.unregister() self.stack_process = None rospy.loginfo("Cleanup finished") def on_vehicle_control(self, data): """ callback if a new vehicle control command is received """ cmd = carla.VehicleControl() cmd.throttle = data.throttle cmd.steer = data.steer cmd.brake = data.brake cmd.hand_brake = data.hand_brake cmd.reverse = data.reverse cmd.gear = data.gear cmd.manual_gear_shift = data.manual_gear_shift self.current_control = cmd if not self.vehicle_control_event.is_set(): self.vehicle_control_event.set() # After the first vehicle control is sent out, it is possible to use the stepping mode self.step_mode_possible = True def build_camera_info(self, attributes): # pylint: disable=no-self-use """ Private function to compute camera info camera info doesn't change over time """ camera_info = CameraInfo() # store info without header camera_info.header = None camera_info.width = int(attributes['width']) camera_info.height = int(attributes['height']) camera_info.distortion_model = 'plumb_bob' cx = camera_info.width / 2.0 cy = camera_info.height / 2.0 fx = camera_info.width / ( 2.0 * math.tan(float(attributes['fov']) * math.pi / 360.0)) fy = fx camera_info.K = [fx, 0, cx, 0, fy, cy, 0, 0, 1] camera_info.D = [0, 0, 0, 0, 0] camera_info.R = [1.0, 0, 0, 0, 1.0, 0, 0, 0, 1.0] camera_info.P = [fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1.0, 0] return camera_info def publish_plan(self): """ publish the global plan """ msg = Path() msg.header.frame_id = "/map" msg.header.stamp = rospy.Time.now() for wp in self._global_plan_world_coord: pose = PoseStamped() pose.pose.position.x = wp[0].location.x pose.pose.position.y = -wp[0].location.y pose.pose.position.z = wp[0].location.z quaternion = tf.transformations.quaternion_from_euler( 0, 0, -math.radians(wp[0].rotation.yaw)) pose.pose.orientation.x = quaternion[0] pose.pose.orientation.y = quaternion[1] pose.pose.orientation.z = quaternion[2] pose.pose.orientation.w = quaternion[3] msg.poses.append(pose) rospy.loginfo("Publishing Plan...") self.waypoint_publisher.publish(msg) def sensors(self): """ Define the sensor suite required by the agent :return: a list containing the required sensors """ raise NotImplementedError( "This function has to be implemented by the derived classes") def get_header(self): """ Returns ROS message header """ header = Header() header.stamp = rospy.Time.from_sec(self.timestamp) return header def publish_lidar(self, sensor_id, data): """ Function to publish lidar data """ header = self.get_header() header.frame_id = 'ego_vehicle/lidar/{}'.format(sensor_id) lidar_data = numpy.frombuffer( data, dtype=numpy.float32) lidar_data = numpy.reshape( lidar_data, (int(lidar_data.shape[0] / 3), 3)) # we take the oposite of y axis # (as lidar point are express in left handed coordinate system, and ros need right handed) # we need a copy here, because the data are read only in carla numpy # array lidar_data = -1.0 * lidar_data # we also need to permute x and y lidar_data = lidar_data[..., [1, 0, 2]] msg = create_cloud_xyz32(header, lidar_data) self.publisher_map[sensor_id].publish(msg) def publish_gnss(self, sensor_id, data): """ Function to publish gnss data """ msg = NavSatFix() msg.header = self.get_header() msg.header.frame_id = 'gps' msg.latitude = data[0] msg.longitude = data[1] msg.altitude = data[2] msg.status.status = NavSatStatus.STATUS_SBAS_FIX # pylint: disable=line-too-long msg.status.service = NavSatStatus.SERVICE_GPS | NavSatStatus.SERVICE_GLONASS | NavSatStatus.SERVICE_COMPASS | NavSatStatus.SERVICE_GALILEO # pylint: enable=line-too-long self.publisher_map[sensor_id].publish(msg) def publish_camera(self, sensor_id, data): """ Function to publish camera data """ msg = self.cv_bridge.cv2_to_imgmsg(data, encoding='bgra8') # the camera data is in respect to the camera's own frame msg.header = self.get_header() msg.header.frame_id = 'ego_vehicle/camera/rgb/{}'.format(sensor_id) cam_info = self.id_to_camera_info_map[sensor_id] cam_info.header = msg.header self.publisher_map[sensor_id + '_info'].publish(cam_info) self.publisher_map[sensor_id].publish(msg) def publish_can(self, sensor_id, data): """ publish can data """ if not self.vehicle_info_publisher: self.vehicle_info_publisher = rospy.Publisher( '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True) info_msg = CarlaEgoVehicleInfo() for wheel in data['wheels']: wheel_info = CarlaEgoVehicleInfoWheel() wheel_info.tire_friction = wheel['tire_friction'] wheel_info.damping_rate = wheel['damping_rate'] wheel_info.steer_angle = wheel['steer_angle'] wheel_info.disable_steering = wheel['disable_steering'] info_msg.wheels.append(wheel_info) info_msg.max_rpm = data['max_rpm'] info_msg.moi = data['moi'] info_msg.damping_rate_full_throttle = data['damping_rate_full_throttle'] info_msg.damping_rate_zero_throttle_clutch_disengaged = data['damping_rate_zero_throttle_clutch_disengaged'] info_msg.use_gear_autobox = data['use_gear_autobox'] info_msg.clutch_strength = data['clutch_strength'] info_msg.mass = data['mass'] info_msg.drag_coefficient = data['drag_coefficient'] info_msg.center_of_mass.x = data['center_of_mass']['x'] info_msg.center_of_mass.y = data['center_of_mass']['y'] info_msg.center_of_mass.z = data['center_of_mass']['z'] self.vehicle_info_publisher.publish(info_msg) msg = CarlaEgoVehicleStatus() msg.header = self.get_header() msg.velocity = data['speed'] self.speed = data['speed'] # msg.acceleration msg.control.throttle = self.current_control.throttle msg.control.steer = self.current_control.steer msg.control.brake = self.current_control.brake msg.control.hand_brake = self.current_control.hand_brake msg.control.reverse = self.current_control.reverse msg.control.gear = self.current_control.gear msg.control.manual_gear_shift = self.current_control.manual_gear_shift self.vehicle_status_publisher.publish(msg) def publish_hd_map(self, sensor_id, data): """ publish hd map data """ roll = -math.radians(data['transform']['roll']) pitch = -math.radians(data['transform']['pitch']) yaw = -math.radians(data['transform']['yaw']) quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw) x = data['transform']['x'] y = -data['transform']['y'] z = data['transform']['z'] if self.odometry_publisher: odometry = Odometry() odometry.header.frame_id = 'map' odometry.header.stamp = rospy.Time.from_sec(self.timestamp) odometry.child_frame_id = 'base_link' odometry.pose.pose.position.x = x odometry.pose.pose.position.y = y odometry.pose.pose.position.z = z odometry.pose.pose.orientation.x = quat[0] odometry.pose.pose.orientation.y = quat[1] odometry.pose.pose.orientation.z = quat[2] odometry.pose.pose.orientation.w = quat[3] odometry.twist.twist.linear.x = self.speed odometry.twist.twist.linear.y = 0 odometry.twist.twist.linear.z = 0 self.odometry_publisher.publish(odometry) if self.world_info_publisher: # extract map name map_name = os.path.basename(data['map_file'])[:-4] if self.current_map_name != map_name: self.current_map_name = map_name world_info = CarlaWorldInfo() world_info.map_name = self.current_map_name world_info.opendrive = data['opendrive'] self.world_info_publisher.publish(world_info) if self.map_file_publisher: self.map_file_publisher.publish(data['map_file']) def use_stepping_mode(self): # pylint: disable=no-self-use """ Overload this function to use stepping mode! """ return False def run_step(self, input_data, timestamp): """ Execute one step of navigation. """ self.vehicle_control_event.clear() self.timestamp = timestamp self.clock_publisher.publish(Clock(rospy.Time.from_sec(timestamp))) # check if stack is still running if self.stack_process and self.stack_process.poll() is not None: raise RuntimeError("Stack exited with: {} {}".format( self.stack_process.returncode, self.stack_process.communicate()[0])) # publish global plan to ROS once if self._global_plan_world_coord and not self.global_plan_published: self.global_plan_published = True self.publish_plan() new_data_available = False # publish data of all sensors for key, val in input_data.items(): new_data_available = True sensor_type = self.id_to_sensor_type_map[key] if sensor_type == 'sensor.camera.rgb': self.publish_camera(key, val[1]) elif sensor_type == 'sensor.lidar.ray_cast': self.publish_lidar(key, val[1]) elif sensor_type == 'sensor.other.gnss': self.publish_gnss(key, val[1]) elif sensor_type == 'sensor.can_bus': self.publish_can(key, val[1]) elif sensor_type == 'sensor.hd_map': self.publish_hd_map(key, val[1]) else: raise TypeError("Invalid sensor type: {}".format(sensor_type)) if self.use_stepping_mode(): if self.step_mode_possible and new_data_available: self.vehicle_control_event.wait() # if the stepping mode is not used or active, there is no need to wait here return self.current_control ================================================ FILE: scenario_runner/srunner/autoagents/sensor_interface.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ This file containts CallBack class and SensorInterface, responsible of handling the use of sensors for the agents """ import copy import logging import numpy as np import carla class CallBack(object): """ Class the sensors listen to in order to receive their data each frame """ def __init__(self, tag, sensor, data_provider): """ Initializes the call back """ self._tag = tag self._data_provider = data_provider self._data_provider.register_sensor(tag, sensor) def __call__(self, data): """ call function """ if isinstance(data, carla.Image): self._parse_image_cb(data, self._tag) elif isinstance(data, carla.LidarMeasurement): self._parse_lidar_cb(data, self._tag) elif isinstance(data, carla.GnssMeasurement): self._parse_gnss_cb(data, self._tag) else: logging.error('No callback method for this sensor.') # Parsing CARLA physical Sensors def _parse_image_cb(self, image, tag): """ parses cameras """ array = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) array = copy.deepcopy(array) array = np.reshape(array, (image.height, image.width, 4)) self._data_provider.update_sensor(tag, array, image.frame) def _parse_lidar_cb(self, lidar_data, tag): """ parses lidar sensors """ points = np.frombuffer(lidar_data.raw_data, dtype=np.dtype('f4')) points = copy.deepcopy(points) points = np.reshape(points, (int(points.shape[0] / 3), 3)) self._data_provider.update_sensor(tag, points, lidar_data.frame) def _parse_gnss_cb(self, gnss_data, tag): """ parses gnss sensors """ array = np.array([gnss_data.latitude, gnss_data.longitude, gnss_data.altitude], dtype=np.float64) self._data_provider.update_sensor(tag, array, gnss_data.frame) class SensorInterface(object): """ Class that contains all sensor data """ def __init__(self): """ Initializes the class """ self._sensors_objects = {} self._data_buffers = {} self._timestamps = {} def register_sensor(self, tag, sensor): """ Registers the sensors """ if tag in self._sensors_objects: raise ValueError("Duplicated sensor tag [{}]".format(tag)) self._sensors_objects[tag] = sensor self._data_buffers[tag] = None self._timestamps[tag] = -1 def update_sensor(self, tag, data, timestamp): """ Updates the sensor """ if tag not in self._sensors_objects: raise ValueError("The sensor with tag [{}] has not been created!".format(tag)) self._data_buffers[tag] = data self._timestamps[tag] = timestamp def all_sensors_ready(self): """ Checks if all the sensors have sent data at least once """ for key in self._sensors_objects: if self._data_buffers[key] is None: return False # for k, v in self._sensors_objects.items(): # print(k, v, v.get_transformer().get_matrix(), flush=True) return True def get_data(self): """ Returns the data of a sensor """ data_dict = {} for key in self._sensors_objects: data_dict[key] = (self._timestamps[key], self._data_buffers[key]) return data_dict ================================================ FILE: scenario_runner/srunner/data/all_towns_traffic_scenarios1_3_4.json ================================================ { "available_scenarios": [ { "Town01": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "167.69", "y": "1.93", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "165.10", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "373.9", "y": "-2.4", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.53", "y": "37.27", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "234.28", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "199.78", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "168.51", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "134.1", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "94.27", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "59.77", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.24", "y": "-1.87", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "158.80", "y": "36.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.17", "y": "-1.91", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "92.99", "y": "35.91", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "87.99", "y": "20.43", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.87", "y": "55.22", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.47", "y": "94.86", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.56", "y": "129.21", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.35", "y": "160.10", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "127.21", "y": "195.29", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.28", "y": "59.38", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "153.78", "y": "20.38", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "53.0", "y": "330.25", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.86", "y": "292.27", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "300.57", "y": "331.2", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "334.60", "y": "291.92", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario4" } ], "Town02": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.28", "y": "161.41", "yaw": "90.0", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "23.72", "y": "187.41", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario4" } ], "Town03": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -44.77, "y": 197.2, "yaw": 187.0, "z": 1.74 } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0.0", "x": "-73.64797973632812", "y": "165.80230712890625", "yaw": "257.414306640625", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -77.8, "y": 34.5, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.094234466552734", "y": "69.08776092529297", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 244.44, "y": 44.28, "yaw": 271.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "241.04603576660156", "y": "44.19745635986328", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 46.52, "y": -196.33, "yaw": 1.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "46.43220520019531", "y": "-192.8362274169922", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.6, "y": -163.36, "yaw": 91.0, "z": 1.82 } }, { "transform": { "pitch": "360.0", "x": "-3.4487547874450684", "y": "-163.4599151611328", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } }, { "transform": { "pitch": "360.0", "x": "244.55511474609375", "y": "43.866703033447266", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -37.73, "y": 0.99, "yaw": 7.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 32.76, "y": -8.17, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.66706466674805", "y": "-4.5203680992126465", "yaw": "181.4586181640625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.45, "y": -4.56, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.539730072021484", "y": "-8.024791717529297", "yaw": "181.48350524902344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": {}, "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "28.78", "y": "196.68", "yaw": "180.072144", "z": "0.99" }, { "pitch": "0.0", "x": "27.30", "y": "193.64", "yaw": "180.072144", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario4" } ], "Town04": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -333.24, "y": 435.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-332.98760986328125", "y": "432.04986572265625", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7461853027344", "y": "428.5581970214844", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.5047607421875", "y": "425.0665283203125", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 406.92, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.44630432128906", "y": "403.47784423828125", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.88621520996094", "y": "410.4554138183594", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.60617065429688", "y": "413.9441833496094", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -183.17, "y": 403.29, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-182.87094116210938", "y": "406.9427185058594", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.58535766601562", "y": "410.4310302734375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.29977416992188", "y": "413.91937255859375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -510.3, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-513.669189453125", "y": "92.98770141601562", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6730651855469", "y": "93.22088623046875", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17498779296875", "y": "93.33748626708984", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -514.1, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1750793457031", "y": "93.2253189086914", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6768493652344", "y": "93.33702087402344", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17864990234375", "y": "93.44872283935547", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -13.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-16.640460968017578", "y": "-230.1665802001953", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.651756286621094", "y": "-229.7690887451172", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.15740442276001", "y": "-229.57032775878906", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -487.27, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-483.66375732421875", "y": "245.8326873779297", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6600646972656", "y": "246.06027221679688", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1582336425781", "y": "246.17405700683594", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -483.59, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.15789794921875", "y": "246.0686798095703", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6559753417969", "y": "246.1850128173828", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1540222167969", "y": "246.30136108398438", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -9.69, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.133902549743652", "y": "-230.1801300048828", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.628005981445312", "y": "-230.38319396972656", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.145692825317383", "y": "-229.77401733398438", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 13.24, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "16.350406646728516", "y": "229.65643310546875", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.356184005737305", "y": "229.37210083007812", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.859072208404541", "y": "229.2299346923828", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.3, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624905586242676", "y": "-79.91557312011719", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.124932289123535", "y": "-79.90184020996094", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624959468841553", "y": "-79.88809967041016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.9, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": 16.8, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.859013557434082", "y": "229.3724365234375", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.361806869506836", "y": "229.2326202392578", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.864601135253906", "y": "229.09280395507812", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 432.39, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4604797363281", "y": "435.5253601074219", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.9693603515625", "y": "428.5426025390625", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7237854003906", "y": "425.0512390136719", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 36.18, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3785705566406", "x": "173.44720458984375", "y": "39.27357482910156", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.56666564941406", "y": "32.274593353271484", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.62640380859375", "y": "28.775104522705078", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 34.38, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2730407714844", "x": "6.096894264221191", "y": "37.6077880859375", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.125317096710205", "y": "30.607847213745117", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.139528274536133", "y": "27.10787582397461", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 34.29, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6138916015625", "y": "37.20619201660156", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60450744628906", "y": "30.206199645996094", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.59982299804688", "y": "26.70620346069336", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 33.53, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.24749755859375", "y": "37.024845123291016", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.2925109863281", "y": "30.02499008178711", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.31500244140625", "y": "26.525062561035156", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 39.53, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.37725830078125", "x": "173.5640869140625", "y": "35.775062561035156", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.6238250732422", "y": "32.275569915771484", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.68356323242188", "y": "28.776081085205078", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 37.73, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2725524902344", "x": "6.124706745147705", "y": "34.107872009277344", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.138918399810791", "y": "30.60790252685547", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.153129577636719", "y": "27.10793113708496", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 37.64, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60472106933594", "y": "33.70620346069336", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6000213623047", "y": "30.206205368041992", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.5953369140625", "y": "26.706209182739258", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 36.88, "yaw": 359.0, "z": 1.13 } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.2915344238281", "y": "33.52505874633789", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3140563964844", "y": "30.025129318237305", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3365478515625", "y": "26.52520179748535", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "0", "x": -12.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.358753204345703", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358806610107422", "y": "-75.72421264648438", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.8588337898254395", "y": "-75.73794555664062", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 14.1, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.49053955078125", "y": "10.631532669067383", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.69122314453125", "y": "17.62865447998047", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.79156494140625", "y": "21.127216339111328", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 11.9, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.3455047607422", "y": "7.477066993713379", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.2260284423828", "y": "14.47604751586914", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.16629028320312", "y": "17.97553825378418", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 9.52, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618186950683594", "y": "16.46259880065918", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 9.11, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41539001464844", "y": "5.670230388641357", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42477416992188", "y": "12.6702241897583", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42945861816406", "y": "16.17022132873535", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 10.45, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.70556640625", "y": "14.126648902893066", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.8155212402344", "y": "17.624921798706055", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.92547607421875", "y": "21.123193740844727", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 7.53, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.215087652206421", "x": "156.21119689941406", "y": "10.975284576416016", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.15145874023438", "y": "14.474775314331055", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.0917205810547", "y": "17.974266052246094", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 5.96, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.604219436645508", "y": "9.462596893310547", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618431091308594", "y": "12.962567329406738", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.63264274597168", "y": "16.462539672851562", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 5.55, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4248504638672", "y": "9.170221328735352", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42955017089844", "y": "12.670218467712402", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.43423461914062", "y": "16.170215606689453", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "0", "x": 385.91, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "382.6264343261719", "y": "-235.0435333251953", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "389.6253967285156", "y": "-235.16390991210938", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1248779296875", "y": "-235.22410583496094", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 409.22, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "412.61456298828125", "y": "-85.36454010009766", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61492919921875", "y": "-85.43766784667969", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1151123046875", "y": "-85.47423553466797", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-15.692474365234375", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.6925630569458", "y": "77.76168823242188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192607879638672", "y": "77.74402618408203", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 412.59, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1151123046875", "y": "-85.43630981445312", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61529541015625", "y": "-85.47286987304688", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.115478515625", "y": "-85.50943756103516", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.97, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.157381057739258", "y": "-229.76759338378906", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.662800788879395", "y": "-229.57290649414062", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.168219089508057", "y": "-229.3782196044922", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.59, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858835220336914", "y": "-75.72463989257812", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358861923217773", "y": "-75.7383804321289", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858889102935791", "y": "-75.75211334228516", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.94, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192610740661621", "y": "77.7610855102539", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.692655563354492", "y": "77.74342346191406", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192700386047363", "y": "77.72576141357422", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 11.74, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.124823570251465", "y": "-79.94327545166016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.1248779296875", "y": "-79.91580963134766", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624904632568359", "y": "-79.90206909179688", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 12.33, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.799628257751465", "y": "76.15249633789062", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.79971694946289", "y": "76.18782043457031", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.299761772155762", "y": "76.20548248291016", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 405.54, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1143493652344", "y": "-85.36266326904297", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6141662597656", "y": "-85.32609558105469", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1147155761719", "y": "-85.435791015625", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.31, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858723640441895", "y": "-75.6960678100586", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.35869598388672", "y": "-75.68233489990234", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858777046203613", "y": "-75.72354125976562", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -8.66, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192425727844238", "y": "77.79782104492188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692380905151367", "y": "77.81548309326172", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192514896392822", "y": "77.76249694824219", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.4, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624799728393555", "y": "-79.9426498413086", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124772071838379", "y": "-79.95638275146484", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624853134155273", "y": "-79.91517639160156", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.63, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "12.299577713012695", "y": "76.15148162841797", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79953384399414", "y": "76.13381958007812", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.2996673583984375", "y": "76.18680572509766", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.53, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.847021102905273", "y": "229.667236328125", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.34402847290039", "y": "229.8119354248047", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.853006362915039", "y": "229.37783813476562", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 428.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4712219238281", "y": "432.01580810546875", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.721435546875", "y": "435.5068664550781", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.97076416015625", "y": "425.0337219238281", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 410.82, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.47103881835938", "y": "406.9908752441406", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.74537658691406", "y": "403.50164794921875", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.92237854003906", "y": "413.9693298339844", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -506.72, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1669006347656", "y": "92.98015594482422", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.664794921875", "y": "92.85853576660156", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.1711120605469", "y": "93.223388671875", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -490.77, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.16552734375", "y": "245.8351593017578", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.66729736328125", "y": "245.72369384765625", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1619567871094", "y": "246.05809020996094", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 32.58, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3799743652344", "x": "173.4454803466797", "y": "35.77303695678711", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.38575744628906", "y": "39.272525787353516", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.56495666503906", "y": "28.774057388305664", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 30.78, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2735595703125", "x": "6.096487998962402", "y": "34.107757568359375", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.082276821136475", "y": "37.60772705078125", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.124910831451416", "y": "27.10781478881836", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 30.69, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61404418945312", "y": "33.7061882019043", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6187286376953", "y": "37.20618438720703", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6046600341797", "y": "26.706195831298828", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 29.93, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2468566894531", "y": "33.5247688293457", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.224365234375", "y": "37.024696350097656", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2918701171875", "y": "26.524913787841797", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 17.41, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.5028991699219", "y": "14.132526397705078", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.4099426269531", "y": "10.633761405944824", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.6888732910156", "y": "21.130056381225586", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 14.49, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3299560546875", "y": "10.977312088012695", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3896942138672", "y": "7.477822303771973", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.21047973632812", "y": "17.976293563842773", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 12.92, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575960159301758", "y": "9.462711334228516", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.561748504638672", "y": "5.962739944458008", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.60438346862793", "y": "16.46265411376953", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 12.51, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41551208496094", "y": "9.170232772827148", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41082763671875", "y": "5.670236110687256", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42489624023438", "y": "16.17022705078125", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "0", "x": 389.55, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "386.126953125", "y": "-235.0426788330078", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.62744140625", "y": "-234.98406982421875", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1259765625", "y": "-235.15989685058594", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 402.0, "y": -85.4, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "405.6141662597656", "y": "-85.36223602294922", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "409.1139831542969", "y": "-85.32567596435547", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6138000488281", "y": "-85.28910827636719", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 16.5, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575634002685547", "y": "12.962740898132324", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.56142234802246", "y": "9.462770462036133", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.547210693359375", "y": "5.962799072265625", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 16.9, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41432189941406", "y": "12.67023754119873", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4096221923828", "y": "9.17024040222168", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.40493774414062", "y": "5.670243740081787", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "0", "x": -6.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-9.628252983093262", "y": "-230.17373657226562", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-13.12211799621582", "y": "-230.38087463378906", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.615983963012695", "y": "-230.5880126953125", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-9.358698844909668", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.858672142028809", "y": "-75.68299865722656", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.358644485473633", "y": "-75.66926574707031", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-8.692384719848633", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.192340850830078", "y": "77.8146743774414", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692296028137207", "y": "77.83233642578125", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 4.69, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.12476921081543", "y": "-79.9434814453125", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "11.62474250793457", "y": "-79.95721435546875", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124715805053711", "y": "-79.970947265625", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.29, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.799537658691406", "y": "76.15229034423828", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "12.299492835998535", "y": "76.13462829589844", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79944896697998", "y": "76.1169662475586", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.19, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "9.344169616699219", "y": "229.6626434326172", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.841078758239746", "y": "229.80970764160156", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.337987899780273", "y": "229.95677185058594", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -494.19, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-490.6671142578125", "y": "245.83995056152344", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-487.1688232421875", "y": "245.7306671142578", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.6705322265625", "y": "245.6213836669922", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -503.22, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-506.6645202636719", "y": "92.97496795654297", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-510.1622009277344", "y": "92.84800720214844", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.659912109375", "y": "92.7210464477539", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 393.1, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "389.62744140625", "y": "-235.04331970214844", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "386.1278991699219", "y": "-234.98617553710938", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.6283874511719", "y": "-234.9290313720703", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 425.47, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.46160888671875", "y": "428.5073547363281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.71630859375", "y": "431.9980773925781", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.97100830078125", "y": "435.4888000488281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 414.14, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.45127868652344", "y": "410.49993896484375", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.72093200683594", "y": "407.0103454589844", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.99057006835938", "y": "403.520751953125", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.6, "y": 21.0, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.5164794921875", "y": "17.633331298828125", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.4296569824219", "y": "14.134408950805664", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.3428039550781", "y": "10.635486602783203", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 29.2, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3813171386719", "x": "173.4475555419922", "y": "32.272560119628906", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.3878173828125", "y": "35.77205276489258", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.32809448242188", "y": "39.271541595458984", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "2", "x": 326.5, "y": 20.8, "yaw": 180.0, "z": 1.7 } }, { "transform": { "pitch": "1.490559458732605", "x": "326.55828857421875", "y": "17.38355827331543", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6180114746094", "y": "13.88406753540039", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6777648925781", "y": "10.384577751159668", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 27.4, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2740478515625", "x": "6.096976280212402", "y": "30.607730865478516", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.082764625549316", "y": "34.10770034790039", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.068553447723389", "y": "37.60767364501953", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 27.31, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61387634277344", "y": "30.206186294555664", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6185760498047", "y": "33.70618438720703", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.62326049804688", "y": "37.206180572509766", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 26.55, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.24761962890625", "y": "30.024702072143555", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.22509765625", "y": "33.52463150024414", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.2026062011719", "y": "37.024559020996094", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 18.7, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.34207153320312", "y": "14.47802734375", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4018096923828", "y": "10.978536605834961", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4615478515625", "y": "7.479046821594238", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario1" } ], "Town05": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.73, "y": 145.88, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 55.87, "y": -145.22, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 101.5, "y": 137.98, "yaw": 164.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.81, "y": 142.49, "yaw": 344.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 136.31, "y": 121.37, "yaw": 137.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 137.75, "y": 125.7, "yaw": 317.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 149.54, "y": 101.12, "yaw": 107.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 152.94, "y": 104.16, "yaw": 287.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": 49.67, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": 51.39, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.37, "y": 16.76, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.55, "y": -16.99, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": -59.22, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": -57.49, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 150.46, "y": -102.24, "yaw": 76.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 154.95, "y": -101.44, "yaw": 255.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 134.58, "y": -127.97, "yaw": 46.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 138.88, "y": -129.5, "yaw": 225.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 98.27, "y": -141.73, "yaw": 11.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.88, "y": -145.47, "yaw": 190.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0", "x": -240.52, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.52142333984375", "y": "-76.91566467285156", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.5221405029297", "y": "-76.96470642089844", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.39, "y": 201.6, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-124.4139175415039", "y": "34.73600387573242", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.6", "y": "29.6", "yaw": "268.398804", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "120.28", "y": "2.26", "yaw": "358.398743", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "151.62", "y": "-30.72", "yaw": "88.888824", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "120.37", "y": "2.29", "yaw": "358.888824", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "151.22", "y": "-30.42", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "155.36", "y": "29.78", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario4" } ], "Town06": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 669.39, "y": 83.38, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "672.7225952148438", "y": "83.4161376953125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7229614257812", "y": "83.34022521972656", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2232055664062", "y": "83.30226135253906", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.723388671875", "y": "83.2643051147461", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.7, "y": 83.5, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.2218627929688", "y": "83.46227264404297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7220458984375", "y": "83.42431640625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2222900390625", "y": "83.3863525390625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7224731445312", "y": "83.34839630126953", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.3, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-8.675992965698242", "y": "-53.622528076171875", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.0, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.176236152648926", "y": "-53.574485778808594", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 2.4, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.828932285308838", "y": "20.622880935668945", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.9, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.3291661739349365", "y": "20.576173782348633", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -16.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-20.065515518188477", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.5749969482422", "y": "-23.56549072265625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-13.065561294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -20.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-23.56553840637207", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-16.565584182739258", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6259765625", "y": "-13.065608024597168", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -23.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.6136016845703", "y": "-20.065608978271484", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.62635803222656", "y": "-16.565631866455078", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.63909912109375", "y": "-13.065655708312988", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -12.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187618255615234", "y": "-16.09782600402832", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.174869537353516", "y": "-19.597803115844727", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -16.1, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187252044677734", "y": "-19.597848892211914", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.212745666503906", "y": "-12.597894668579102", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.91, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.90859985351562", "y": "45.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9071807861328", "y": "48.9715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.90577697753906", "y": "52.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.92, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.91854858398438", "y": "48.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.91714477539062", "y": "52.47157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.92138671875", "y": "41.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9285888671875", "y": "52.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93141174316406", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93283081054688", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 52.88, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9315643310547", "y": "48.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9329833984375", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9344024658203", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -19.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.21311569213867", "y": "-16.097919464111328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.225860595703125", "y": "-12.597942352294922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 658.6, "y": 82.95, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "662.2265625", "y": "82.98932647705078", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.726318359375", "y": "83.02729034423828", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2261352539062", "y": "83.06524658203125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7259521484375", "y": "83.10320281982422", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 662.3, "y": 83.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "665.7197265625", "y": "83.63709259033203", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2195434570312", "y": "83.675048828125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7193603515625", "y": "83.71300506591797", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7201538085938", "y": "83.56117248535156", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.8, "y": 83.17, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.224609375", "y": "83.20713806152344", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7244262695312", "y": "83.2450942993164", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2250366210938", "y": "83.13121795654297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7252197265625", "y": "83.09326171875", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.4, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "12.778694152832031", "y": "276.646728515625", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.77956485748291", "y": "276.75714111328125", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 239.9, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.6988410949707", "y": "243.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68668746948242", "y": "246.61331176757812", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.674537658691406", "y": "250.11329650878906", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -10.2, "y": 213.5, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.720656394958496", "y": "213.4451141357422", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2210917472839355", "y": "213.38990783691406", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6298828125", "y": "138.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6454467773438", "y": "138.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 657.7, "y": 183.15, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "661.1398315429688", "y": "183.1873016357422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6395874023438", "y": "183.2252655029297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.139404296875", "y": "183.2632293701172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6392211914062", "y": "183.30117797851562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 661.7, "y": 183.26, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "664.6388549804688", "y": "183.2918701171875", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.138671875", "y": "183.329833984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6384887695312", "y": "183.36778259277344", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6392822265625", "y": "183.21595764160156", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.658935546875", "y": "138.49703979492188", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.2, "y": 183.37, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.137939453125", "y": "183.40187072753906", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6377563476562", "y": "183.4398193359375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1383666992188", "y": "183.32594299316406", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6385498046875", "y": "183.28799438476562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 668.99, "y": 183.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "671.6359252929688", "y": "183.60870361328125", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6362915039062", "y": "183.5327911376953", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1365356445312", "y": "183.4948272705078", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.63671875", "y": "183.45687866210938", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.3, "y": 183.7, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.1351928710938", "y": "183.6548309326172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6353759765625", "y": "183.6168670654297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1356201171875", "y": "183.5789031982422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6358032226562", "y": "183.54095458984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -13.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58847045898438", "y": "-16.565494537353516", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.57571411132812", "y": "-20.065471649169922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.56297302246094", "y": "-23.565448760986328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.278183937072754", "y": "276.6419982910156", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.777749061584473", "y": "276.5867919921875", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3915710449219", "y": "45.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3932800292969", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39495849609375", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3915100097656", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3931884765625", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3880920410156", "y": "41.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3863830566406", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39154052734375", "y": "52.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "45.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3864440917969", "y": "41.744102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3847351074219", "y": "38.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 52.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.27813720703125", "y": "48.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27642822265625", "y": "45.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27471923828125", "y": "41.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27301025390625", "y": "38.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.4, "y": 138.59, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.39260864257812", "y": "135.4395294189453", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.49070739746094", "y": "138.93931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.48249816894531", "y": "135.43931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -239.6, "y": 240.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-239.59410095214844", "y": "243.68092346191406", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58779907226562", "y": "247.180908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58151245117188", "y": "250.680908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -359.5, "y": 58.1, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-362.68389892578125", "y": "57.73311233520508", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-366.160888671875", "y": "57.33245086669922", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.63787841796875", "y": "56.931793212890625", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -13.9, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.298583984375", "y": "-17.034290313720703", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28582763671875", "y": "-20.53426742553711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.2731018066406", "y": "-24.034242630004883", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 503.51, "y": -10.4, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "503.5177307128906", "y": "-13.939313888549805", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5253601074219", "y": "-17.439306259155273", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.53302001953125", "y": "-20.93929672241211", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5406494140625", "y": "-24.439289093017578", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 38.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.401611328125", "y": "41.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.405029296875", "y": "48.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4067077636719", "y": "52.24409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 38.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.40155029296875", "y": "41.81858444213867", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40325927734375", "y": "45.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40496826171875", "y": "48.818580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40667724609375", "y": "52.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 41.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29331970214844", "y": "45.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29661560058594", "y": "48.73708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29991149902344", "y": "52.23708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 138.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3869323730469", "y": "141.3854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3725891113281", "y": "144.8854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3582458496094", "y": "148.38539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3439025878906", "y": "151.88536071777344", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 137.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3870544433594", "y": "140.75856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3727111816406", "y": "144.25852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3583679199219", "y": "147.7584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3440246582031", "y": "151.2584686279297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.3, "y": 136.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "140.13125610351562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2720184326172", "y": "143.6312255859375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.25767517089844", "y": "147.13119506835938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2433319091797", "y": "150.63116455078125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.1, "y": 135.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 333.2, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1989440917969", "y": "241.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.19775390625", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.196533203125", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1953430175781", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89891052246094", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89772033691406", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8965301513672", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8953399658203", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 238.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09896469116211", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09777069091797", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.096576690673828", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.095382690429688", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } } ], "scenario_type": "Scenario4" } ] } ] } ================================================ FILE: scenario_runner/srunner/data/all_towns_traffic_scenarios1_3_4_8.json ================================================ { "available_scenarios": [ { "Town01": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "304.75", "y": "199.22", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "319.64", "y": "-2.20", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "107.98", "y": "330.64", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.95", "y": "326.51", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.68", "y": "199.13", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "317.15", "y": "195.0", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "108.81", "y": "133.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "319.79", "y": "129.41", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "322.54", "y": "55.39", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "170.84", "y": "59.52", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "167.69", "y": "1.93", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "316.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "2.52", "y": "163.40", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.81", "y": "163.80", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.61", "y": "10.73", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "317.80", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "165.10", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "396.30", "y": "165.30", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "392.17", "y": "12.30", "yaw": "89", "z": "1.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "299.99", "y": "2.0", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "373.1", "y": "-2.3", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.96", "y": "31.64", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "335.5", "y": "94.65", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.55", "y": "168.65", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.55", "y": "133.65", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "334.85", "y": "20.61", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.35", "y": "94.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.35", "y": "59.61", "yaw": "0", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "119.51", "y": "1.44", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "192.90", "y": "-1.61", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "158.10", "y": "31.4", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "53.61", "y": "2.3", "yaw": "0.000031", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.94", "y": "-2.32", "yaw": "180.000015", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.45", "y": "30.84", "yaw": "270", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.74", "y": "94.29", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.47", "y": "20.20", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.53", "y": "55.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "92.46", "y": "168.64", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.50", "y": "94.86", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.33", "y": "129.48", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "91.92", "y": "234.16", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "88.42", "y": "160.16", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.42", "y": "195.16", "yaw": "180", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "192.94", "y": "55.69", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "118.94", "y": "60.19", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "153.94", "y": "26.19", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "127.39", "y": "326.52", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "53.12", "y": "330.65", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.23", "y": "297.43", "yaw": "90", "z": "1.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "373.65", "y": "326.84", "yaw": "180.000046", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "300.15", "y": "330.50", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.81", "y": "297.3", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "373.9", "y": "-2.4", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "339.53", "y": "37.27", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.12", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "234.28", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "199.78", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "165.78", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "168.51", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "134.1", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "100.1", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "338.54", "y": "94.27", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "299.54", "y": "59.77", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "334.54", "y": "25.77", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.24", "y": "-1.87", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "158.80", "y": "36.61", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.46", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.17", "y": "-1.91", "yaw": "180.000015", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "92.99", "y": "35.91", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.81", "y": "2.26", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "87.99", "y": "20.43", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.87", "y": "55.22", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "88.85", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.47", "y": "94.86", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.56", "y": "129.21", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "163.42", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.35", "y": "160.10", "yaw": "90.0", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "127.21", "y": "195.29", "yaw": "180.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "92.55", "y": "228.60", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.28", "y": "59.38", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "153.78", "y": "20.38", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.78", "y": "55.38", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "53.0", "y": "330.25", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "87.86", "y": "292.27", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "121.57", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "300.57", "y": "331.2", "yaw": "0.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "334.60", "y": "291.92", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.55", "y": "326.42", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "374.11", "y": "326.55", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "335.4", "y": "291.71", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "305.22", "y": "330.72", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "298.83", "y": "2.14", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "339.27", "y": "36.68", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "368.15", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "159.40", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "198.40", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "228.40", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "93.73", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "132.73", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "162.73", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "334.34", "y": "20.29", "yaw": "90.000031", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "299.84", "y": "59.29", "yaw": "0.000031", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "338.84", "y": "89.29", "yaw": "270", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "119.65", "y": "2.9", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "158.9", "y": "35.84", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "187.49", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "52.70", "y": "2.18", "yaw": "0.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "93.4", "y": "36.17", "yaw": "270.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "122.3", "y": "-2.4", "yaw": "180", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.76", "y": "93.99", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "126.92", "y": "55.94", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "25.23", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "92.78", "y": "168.67", "yaw": "270.000061", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "126.47", "y": "129.17", "yaw": "180.000061", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "99.90", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "91.75", "y": "234.27", "yaw": "270.000061", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "127.25", "y": "195.7", "yaw": "180.000076", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "88.25", "y": "165.27", "yaw": "90", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.25", "y": "55.49", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "153.76", "y": "21.2", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "124.35", "y": "59.68", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "127.51", "y": "326.45", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "88.16", "y": "291.69", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "58.44", "y": "330.72", "yaw": "0", "z": "1.0" } } ], "scenario_type": "Scenario8" } ], "Town02": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "180.93", "y": "105.31", "yaw": "180", "z": "1.22" } }, { "transform": { "pitch": "0", "x": "7.63", "y": "109.91", "yaw": "359", "z": "1.22" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "-3.60", "y": "218.56", "yaw": "270.000061", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "-7.35", "y": "157.56", "yaw": "90.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "26.65", "y": "187.56", "yaw": "180", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "12.13", "y": "306.53", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.35", "y": "272.9", "yaw": "90.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "74.67", "y": "302.64", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "41.52", "y": "206.94", "yaw": "90.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "75.91", "y": "236.67", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "45.67", "y": "270.24", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "14.4", "y": "191.66", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "76.63", "y": "187.29", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "46.7", "y": "220.74", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "99.5", "y": "191.74", "yaw": "0.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "166.52", "y": "187.47", "yaw": "180.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "136.12", "y": "220.86", "yaw": "270", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.38", "y": "157.31", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.86", "y": "221.13", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.20", "y": "191.59", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "189.56", "y": "207.53", "yaw": "90.0", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "193.79", "y": "269.16", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "160.25", "y": "240.93", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "165.70", "y": "237.8", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "103.35", "y": "241.41", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "132.5", "y": "207.50", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "46.1", "y": "271.2", "yaw": "270.000061", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "41.99", "y": "206.39", "yaw": "90.000061", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.27", "y": "236.54", "yaw": "180", "z": "1.21" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "75.47", "y": "302.34", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "12.18", "y": "306.46", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "272.34", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.28", "y": "161.41", "yaw": "90.0", "z": "1.22" } ], "right": [ { "pitch": "0.0", "x": "23.72", "y": "187.41", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-3.28", "y": "221.41", "yaw": "270", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "75.82", "y": "187.67", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "46.2", "y": "221.10", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.82", "y": "191.57", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "166.6", "y": "187.54", "yaw": "180.000015", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "136.6", "y": "221.2", "yaw": "270.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.60", "y": "191.58", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.72", "y": "221.21", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "160.15", "y": "191.57", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.49", "y": "157.87", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "193.82", "y": "268.10", "yaw": "270.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "159.79", "y": "240.97", "yaw": "0.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "189.41", "y": "207.2", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.73", "y": "240.93", "yaw": "0.000031", "z": "1.21" } ], "right": [ { "pitch": "0.0", "x": "132.15", "y": "207.54", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "236.94", "yaw": "180", "z": "1.21" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "45.82", "y": "270.45", "yaw": "270.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "75.58", "y": "236.78", "yaw": "180.000015", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "41.37", "y": "207.4", "yaw": "90", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.92", "y": "302.50", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "41.46", "y": "272.5", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "11.57", "y": "306.34", "yaw": "0", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-3.50", "y": "217.35", "yaw": "270.0", "z": "1.22" } ], "left": [ { "pitch": "0.0", "x": "22.50", "y": "187.35", "yaw": "180.0", "z": "1.22" } ] }, "transform": { "pitch": "0", "x": "-7.50", "y": "157.35", "yaw": "90", "z": "1.22" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "15.53", "y": "191.84", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "45.92", "y": "221.47", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "75.26", "y": "187.47", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.4", "y": "191.76", "yaw": "0.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "136.18", "y": "220.83", "yaw": "270.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "166.0", "y": "187.45", "yaw": "180", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.26", "y": "157.74", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.14", "y": "191.53", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.63", "y": "221.27", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "189.53", "y": "207.38", "yaw": "90.000031", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "160.26", "y": "240.99", "yaw": "0.000031", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "193.71", "y": "270.70", "yaw": "270", "z": "1.21" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "165.63", "y": "236.96", "yaw": "180.000015", "z": "1.21" } ], "left": [ { "pitch": "0.0", "x": "132.4", "y": "207.55", "yaw": "90.0", "z": "1.21" } ] }, "transform": { "pitch": "0", "x": "102.53", "y": "241.10", "yaw": "0", "z": "1.21" } } ], "scenario_type": "Scenario8" } ], "Town03": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 231.4, "y": 23.39, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -44.77, "y": 197.2, "yaw": 187.0, "z": 1.74 } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0.0", "x": "-73.64797973632812", "y": "165.80230712890625", "yaw": "257.414306640625", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "transform": { "pitch": "0", "x": 119.41, "y": -132.31, "yaw": 1.0, "z": 9.0 } }, { "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -77.8, "y": 34.5, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.094234466552734", "y": "69.08776092529297", "yaw": "269.637451171875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 244.44, "y": 44.28, "yaw": 271.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "241.04603576660156", "y": "44.19745635986328", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 46.52, "y": -196.33, "yaw": 1.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "46.43220520019531", "y": "-192.8362274169922", "yaw": "1.439544677734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.6, "y": -163.36, "yaw": 91.0, "z": 1.82 } }, { "transform": { "pitch": "360.0", "x": "-3.4487547874450684", "y": "-163.4599151611328", "yaw": "91.41353607177734", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } }, { "transform": { "pitch": "360.0", "x": "244.55511474609375", "y": "43.866703033447266", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -37.73, "y": 0.99, "yaw": 7.0, "z": 1.8 } }, { "transform": { "pitch": "0", "x": 32.76, "y": -8.17, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.66706466674805", "y": "-4.5203680992126465", "yaw": "181.4586181640625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.45, "y": -4.56, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "32.539730072021484", "y": "-8.024791717529297", "yaw": "181.48350524902344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -125.3, "y": 45.81, "yaw": 133.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -145.69, "y": 92.34, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -115.5, "y": 30.75, "yaw": 134.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "transform": { "pitch": "0", "x": 110.65, "y": -7.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "110.58321380615234", "y": "-3.3287293910980225", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "352", "x": 77.66, "y": -36.16, "yaw": 91.0, "z": 5.25 } }, { "transform": { "pitch": "352", "x": 148.52, "y": -35.96, "yaw": 91.0, "z": 4.15 } }, { "transform": { "pitch": "0", "x": 182.48, "y": -6.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "182.4210662841797", "y": "-2.2556450366973877", "yaw": "-179.14419555664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 239.39, "y": 113.42, "yaw": 270.0, "z": 2.36 } }, { "transform": { "pitch": "358.8267822265625", "x": "242.86146545410156", "y": "113.50442504882812", "yaw": "271.3932189941406", "z": "0.5679125189781189" } }, { "transform": { "pitch": "0", "x": 232.36, "y": 113.29, "yaw": 90.0, "z": 2.46 } }, { "transform": { "pitch": "1.1732286214828491", "x": "228.8646240234375", "y": "113.20498657226562", "yaw": "91.3932113647461", "z": "0.5687512755393982" } }, { "transform": { "pitch": "0", "x": -84.6, "y": 167.1, "yaw": 78.0, "z": 1.53 } }, { "transform": { "pitch": "360.0", "x": "-87.55733489990234", "y": "167.6916961669922", "yaw": "438.6856689453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 203.9, "yaw": 0.0, "z": 2.5 } }, { "transform": { "pitch": "361.12353515625", "x": "52.918731689453125", "y": "207.39906311035156", "yaw": "359.8570556640625", "z": "0.2592363655567169" } }, { "transform": { "pitch": "0", "x": -84.66, "y": 69.48, "yaw": 90.0, "z": 2.62 } }, { "transform": { "pitch": "-0.14853577315807343", "x": "-88.17547607421875", "y": "69.48959350585938", "yaw": "89.84374237060547", "z": "0.8320345282554626" } }, { "transform": { "pitch": "0", "x": -77.7, "y": 69.11, "yaw": 270.0, "z": 2.62 } }, { "transform": { "pitch": "360.11688232421875", "x": "-74.1764907836914", "y": "69.10039520263672", "yaw": "269.84375", "z": "0.8328475952148438" } }, { "transform": { "pitch": "0", "x": -85.2, "y": -78.9, "yaw": 90.0, "z": 0.97 } }, { "transform": { "pitch": "-0.23343351483345032", "x": "-88.58015441894531", "y": "-78.89077758789062", "yaw": "89.84374237060547", "z": "-0.8594440817832947" } }, { "transform": { "pitch": "0", "x": -78.4, "y": -78.46, "yaw": 270.0, "z": 0.96 } }, { "transform": { "pitch": "360.2005920410156", "x": "-74.5789566040039", "y": "-78.47042846679688", "yaw": "269.84375", "z": "-0.8611809015274048" } }, { "transform": { "pitch": "0", "x": 4.89, "y": -78.46, "yaw": 270.0, "z": 1.81 } }, { "transform": { "pitch": "0.0", "x": "8.455883979797363", "y": "-78.37200164794922", "yaw": "-88.58646392822266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.34, "y": 69.48, "yaw": 90.0, "z": 1.77 } }, { "transform": { "pitch": "0.0", "x": "-9.903441429138184", "y": "69.50254821777344", "yaw": "89.63746643066406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.91, "y": 196.87, "yaw": 179.0, "z": 2.5 } }, { "transform": { "pitch": "-1.1242796182632446", "x": "52.90134048461914", "y": "193.39906311035156", "yaw": "179.85704040527344", "z": "0.25958043336868286" } }, { "transform": { "pitch": "0", "x": 235.35, "y": -145.9, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "238.2660675048828", "y": "-146.11538696289062", "yaw": "85.77556610107422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 236.45, "y": -53.93, "yaw": 91.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "232.93157958984375", "y": "-54.01557540893555", "yaw": "91.3932113647461", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 243.51, "y": -54.21, "yaw": 270.0, "z": 1.79 } }, { "transform": { "pitch": "360.0", "x": "246.9384002685547", "y": "-54.12661361694336", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 238.58, "y": -144.85, "yaw": 91.0, "z": 1.83 } }, { "transform": { "pitch": "0.0", "x": "234.85678100585938", "y": "-144.6316375732422", "yaw": "86.64344024658203", "z": "0.0" } }, { "transform": { "pitch": "1", "x": 141.91, "y": 203.68, "yaw": 0.0, "z": 4.1 } }, { "transform": { "pitch": "361.2748107910156", "x": "141.91873168945312", "y": "207.17698669433594", "yaw": "359.8570556640625", "z": "2.23475980758667" } }, { "transform": { "pitch": "0", "x": 245.35, "y": -129.63, "yaw": 270.0, "z": 1.83 } }, { "transform": { "pitch": "360.0", "x": "248.77268981933594", "y": "-129.54676818847656", "yaw": "271.3932189941406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 185.95, "y": -197.37, "yaw": 0.0, "z": 1.78 } }, { "transform": { "pitch": "0.0", "x": "185.9499969482422", "y": "-193.89999389648438", "yaw": "0.0", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 230.94, "y": -174.85, "yaw": 65.0, "z": 1.8 } }, { "transform": { "pitch": "0.0", "x": "227.7465362548828", "y": "-173.4008331298828", "yaw": "65.59180450439453", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 237.1, "y": -178.9, "yaw": 245.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "240.00001525878906", "y": "-180.2597198486328", "yaw": "244.8795623779297", "z": "0.0" } }, { "transform": { "pitch": "358", "x": 160.88, "y": 193.2, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.260597586631775", "x": "161.10287475585938", "y": "196.4036102294922", "yaw": "176.02037048339844", "z": "2.6701090335845947" } }, { "transform": { "pitch": "0", "x": 46.36, "y": -203.4, "yaw": 181.0, "z": 1.8 } }, { "transform": { "pitch": "358", "x": 160.61, "y": 196.49, "yaw": 179.0, "z": 4.1 } }, { "transform": { "pitch": "-1.274809718132019", "x": "160.38092041015625", "y": "192.94418334960938", "yaw": "176.3036651611328", "z": "2.6584856510162354" } }, { "transform": { "pitch": "0", "x": 240.99, "y": 43.78, "yaw": 271.0, "z": 2.44 } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.43", "y": "113.35", "yaw": "271.362183", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "200.87", "y": "62.39", "yaw": "1.362183", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "234.5481719970703", "y": "23.466564178466797", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 234.52, "y": 23.65, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "239.69", "y": "113.45", "yaw": "270.59845", "z": "2.5" } ], "right": [ { "pitch": "0.0", "x": "199.69", "y": "62.39", "yaw": "0.598419", "z": "2.5" } ] }, "transform": { "pitch": "0.0", "x": "231.04473876953125", "y": "23.565475463867188", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "234.32", "y": "22.71", "yaw": "89.268646", "z": "2.23" }, { "pitch": "0.0", "x": "231.8", "y": "22.75", "yaw": "89.268646", "z": "2.23" } ], "right": [ { "pitch": "0.0", "x": "239.40", "y": "112.66", "yaw": "269.268646", "z": "2.5" } ] }, "transform": { "pitch": "0", "x": 200.43, "y": 62.24, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-114.41", "y": "-135.62", "yaw": "0.91452", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.91", "y": "-101.82", "yaw": "270.91452", "z": "0.92" }, { "pitch": "0.0", "x": "-85.47", "y": "-101.76", "yaw": "270.91452", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-84.46", "y": "-170.55", "yaw": "90.91449", "z": "0.92" }, { "pitch": "0.0", "x": "-88.39", "y": "-170.61", "yaw": "90.91449", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -46.1, "y": -140.7, "yaw": 180.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -74.68, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-83.83", "y": "-174.67", "yaw": "92.183899", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.45", "y": "-135.50", "yaw": "0.061707", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.56", "y": "-139.47", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-78.15487670898438", "y": "-106.30052185058594", "yaw": "269.84375", "z": "-0.374824196100235" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -78.1, "y": -106.31, "yaw": 270.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.64", "y": "-175.22", "yaw": "90.333191", "z": "0.92" }, { "pitch": "0.0", "x": "-88.9", "y": "-175.24", "yaw": "90.333191", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-112.7", "y": "-135.63", "yaw": "0.070038", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-40.0", "y": "-139.30", "yaw": "180.333191", "z": "0.92" } ] }, "transform": { "pitch": "361.3090515136719", "x": "-74.6549072265625", "y": "-106.31939697265625", "yaw": "269.84375", "z": "-0.3746110796928406" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -88.11, "y": -170.3, "yaw": 90.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.11", "y": "-170.3", "yaw": "90.99231", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-88.12", "y": "-169.33", "yaw": "90.99231", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.20", "y": "-135.56", "yaw": "0.99231", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-84.04679870605469", "y": "-170.06784057617188", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0", "x": -84.48, "y": -170.3, "yaw": 91.0, "z": 0.92 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.16", "y": "-100.62", "yaw": "269.305237", "z": "0.92" }, { "pitch": "0.0", "x": "-74.51", "y": "-100.63", "yaw": "269.305237", "z": "0.92" } ], "left": [ { "pitch": "0.0", "x": "-41.18", "y": "-139.18", "yaw": "181.411148", "z": "0.92" } ], "right": [ { "pitch": "0.0", "x": "-113.49", "y": "-135.14", "yaw": "1.411133", "z": "0.92" } ] }, "transform": { "pitch": "0.0", "x": "-87.52928924560547", "y": "-170.4742431640625", "yaw": "93.27017974853516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.12", "y": "-139.6", "yaw": "181.239594", "z": "0.95" } ], "left": [ { "pitch": "0.0", "x": "-84.34", "y": "-174.23", "yaw": "91.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-87.72", "y": "-174.7", "yaw": "91.239563", "z": "0.77" } ], "right": [ { "pitch": "0.0", "x": "-78.29", "y": "-102.45", "yaw": "271.239563", "z": "0.77" }, { "pitch": "0.0", "x": "-74.75", "y": "-102.37", "yaw": "271.239563", "z": "0.77" } ] }, "transform": { "pitch": "0", "x": -113.37, "y": -135.68, "yaw": 1.0, "z": 2.7 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0", "x": 9.33, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.12", "y": "-173.5", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.14", "y": "-173.10", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.46", "yaw": "0.320282", "z": "1.16" } ], "right": [ { "pitch": "353.754242", "x": "40.66", "y": "-137.41", "yaw": "180.999588", "z": "4.2" } ] }, "transform": { "pitch": "0.0", "x": "5.609712600708008", "y": "-104.91180419921875", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.44, "y": -167.82, "yaw": 91.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.47", "y": "-100.42", "yaw": "271.386719", "z": "1.0" } ], "left": [ { "pitch": "351.057251", "x": "40.85", "y": "-137.24", "yaw": "181.386688", "z": "3.96" } ], "right": [ { "pitch": "0.0", "x": "-37.90", "y": "-135.27", "yaw": "1.386658", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.15770983695983887", "y": "-167.7312469482422", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": 7.44, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.60", "y": "-198.55", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.70", "y": "-194.74", "yaw": "0.996216", "z": "0.94" } ], "right": [ { "pitch": "0.0", "x": "41.92", "y": "-203.98", "yaw": "180.996216", "z": "0.93" } ] }, "transform": { "pitch": "0.0", "x": "10.55854606628418", "y": "-163.5830535888672", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 10.99, "y": -163.66, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-32.54", "y": "-198.32", "yaw": "0.996216", "z": "0.94" }, { "pitch": "0.0", "x": "-32.63", "y": "-194.70", "yaw": "0.996216", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "7.061770915985107", "y": "-163.75694274902344", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 25.77, "y": -207.44, "yaw": 181.0, "z": 1.0 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "25.680063247680664", "y": "-203.86105346679688", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "359", "x": -32.48, "y": -198.25, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.87", "y": "-204.4", "yaw": "181.643997", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.37", "y": "-163.23", "yaw": "271.643982", "z": "0.93" } ] }, "transform": { "pitch": "360.0", "x": "-32.566158294677734", "y": "-194.82147216796875", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "359", "x": -32.4, "y": -194.71, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "41.32", "y": "-203.84", "yaw": "181.228012", "z": "0.87" } ], "right": [ { "pitch": "0.0", "x": "7.32", "y": "-163.85", "yaw": "271.227997", "z": "0.93" }, { "pitch": "0.0", "x": "10.86", "y": "-163.95", "yaw": "271.227997", "z": "0.92" } ] }, "transform": { "pitch": "360.0", "x": "-32.30937957763672", "y": "-198.31613159179688", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -201.92, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.58008575439453", "y": "-205.50503540039062", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 99.49, "y": -205.37, "yaw": 184.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "0.0", "x": "99.405517578125", "y": "-202.00833129882812", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": {}, "transform": { "pitch": "359", "x": 68.68, "y": -195.79, "yaw": 1.0, "z": 1.4 } }, { "other_actors": {}, "transform": { "pitch": "360.0", "x": "68.59178161621094", "y": "-192.27935791015625", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "359", "x": 53.6, "y": -192.29, "yaw": 1.0, "z": 1.4 } }, { "other_actors": { "front": [ { "pitch": "0.040314", "x": "100.3", "y": "-201.97", "yaw": "181.765335", "z": "1.1" }, { "pitch": "0.040314", "x": "100.46", "y": "-205.33", "yaw": "181.765335", "z": "1.1" } ], "right": [ { "pitch": "359.996887", "x": "86.51", "y": "-181.27", "yaw": "271.76532", "z": "1.2" } ] }, "transform": { "pitch": "360.0", "x": "53.697120666503906", "y": "-196.15476989746094", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "121.60", "y": "-190.81", "yaw": "0.810791", "z": "1.82" } ] }, "transform": { "pitch": "350", "x": 154.6, "y": -164.4, "yaw": 270.0, "z": 4.7 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "0", "x": 122.3, "y": -190.88, "yaw": 1.0, "z": 1.21 } }, { "other_actors": { "right": [ { "pitch": "350.85144", "x": "154.89", "y": "-164.5", "yaw": "271.517822", "z": "5.2" } ] }, "transform": { "pitch": "360.0", "x": "122.3891830444336", "y": "-194.4285430908203", "yaw": "1.439544677734375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "359.324677", "x": "153.91", "y": "-100.74", "yaw": "270.315552", "z": "9.81" } ], "right": [ { "pitch": "358.80191", "x": "119.89", "y": "-131.65", "yaw": "0.600189", "z": "9.67" } ] }, "transform": { "pitch": "12", "x": 150.81, "y": -165.57, "yaw": 90.0, "z": 4.4 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0", "x": 114.84, "y": -76.55, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "left": [ { "pitch": "10.508362", "x": "82.56", "y": "-46.78", "yaw": "271.32608", "z": "6.54" } ] }, "transform": { "pitch": "0.0", "x": "114.74317169189453", "y": "-72.87480926513672", "yaw": "-178.49090576171875", "z": "8.0" } }, { "other_actors": { "right": [ { "pitch": "358.490753", "x": "111.82", "y": "-74.13", "yaw": "180.623871", "z": "11.21" } ] }, "transform": { "pitch": "9", "x": 82.9, "y": -47.14, "yaw": 270.0, "z": 5.72 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -74.43, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.95", "y": "100.94", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.42", "y": "136.53", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-46.26", "y": "131.54", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-77.13905334472656", "y": "166.22161865234375", "yaw": "257.8827209472656", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.12, "y": 101.68, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.9", "y": "166.30", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.89", "y": "131.46", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-116.1", "y": "136.73", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-84.58769989013672", "y": "101.67036437988281", "yaw": "89.84374237060547", "z": "0.3354354798793793" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 5.6, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "102.53", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.10", "y": "134.37", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.11", "y": "130.7", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "2.194162607192993", "y": "163.9115447998047", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.62, "y": 102.9, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.95", "y": "163.28", "yaw": "269.379242", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.52", "y": "130.99", "yaw": "179.379211", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-37.62", "y": "136.34", "yaw": "359.379211", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-6.19218635559082", "y": "102.87830352783203", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-148.92", "y": "-34.67", "yaw": "89.832642", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-110.54", "y": "-3.58", "yaw": "179.832642", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -145.53, "y": 26.3, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-145.48", "y": "30.80", "yaw": "270.041382", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-149.11", "y": "-34.77", "yaw": "90.041351", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -116.7, "y": -3.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.98", "y": "58.91", "yaw": "180.209106", "z": "1.17" } ] }, "transform": { "pitch": "0", "x": 170.37, "y": 99.28, "yaw": 270.0, "z": 1.17 } }, { "other_actors": {}, "transform": { "pitch": "0", "x": 139.75, "y": 62.51, "yaw": 359.0, "z": 1.17 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "170.14", "y": "97.81", "yaw": "268.909027", "z": "2.4" } ] }, "transform": { "pitch": "0", "x": 201.12, "y": 58.8, "yaw": 178.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -77.8, "y": 34.5, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -74.26, "y": 31.95, "yaw": 270.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.17", "y": "-34.11", "yaw": "90.289825", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-121.96", "y": "0.24", "yaw": "0.289825", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-40.36", "y": "-2.78", "yaw": "180.289825", "z": "1.3" } ] }, "transform": { "pitch": "359.0536804199219", "x": "-77.77780151367188", "y": "31.9595947265625", "yaw": "269.84375", "z": "0.13858206570148468" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -88.84, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.84", "y": "40.6", "yaw": "269.153809", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.43", "y": "-3.6", "yaw": "179.153809", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-121.51", "y": "0.26", "yaw": "0.153778", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-84.9437484741211", "y": "-28.880624771118164", "yaw": "89.84374237060547", "z": "-0.26675039529800415" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0", "x": 235.56, "y": -37.12, "yaw": 90.0, "z": 1.8 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "199.18", "y": "5.94", "yaw": "0.053986", "z": "1.80" }, { "pitch": "0.0", "x": "199.18", "y": "9.25", "yaw": "0.053986", "z": "1.80" } ] }, "transform": { "pitch": "0.0", "x": "232.5224609375", "y": "-37.193870544433594", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0", "x": 231.92, "y": -36.82, "yaw": 90.0, "z": 1.79 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "200.67", "y": "6.24", "yaw": "0.053986", "z": "1.79" }, { "pitch": "0.0", "x": "200.35", "y": "9.56", "yaw": "0.053986", "z": "1.79" } ] }, "transform": { "pitch": "0.0", "x": "236.01197814941406", "y": "-36.72048568725586", "yaw": "91.3932113647461", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.84, "y": 170.34, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.3", "y": "196.64", "yaw": "179.39917", "z": "1.0" }, { "pitch": "0.0", "x": "34.5", "y": "194.9", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.265254020690918", "y": "170.36167907714844", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -9.24, "y": 170.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.26", "y": "194.19", "yaw": "181.136978", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-5.764954566955566", "y": "170.3980255126953", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.52, "y": 196.65, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-5.72", "y": "165.25", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.0878860130906105", "x": "28.512041091918945", "y": "193.4599151611328", "yaw": "179.85704040527344", "z": "0.0015862176660448313" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.72, "y": 193.61, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-6.3", "y": "165.50", "yaw": "89.699402", "z": "1.0" }, { "pitch": "0.0", "x": "-9.33", "y": "165.47", "yaw": "89.699402", "z": "1.0" } ] }, "transform": { "pitch": "-0.09670676290988922", "x": "28.72835350036621", "y": "196.95938110351562", "yaw": "179.85704040527344", "z": "0.00192060018889606" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "0", "x": 199.72, "y": 5.93, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.62", "y": "-35.2", "yaw": "90.0", "z": "1.30" }, { "pitch": "0.0", "x": "231.93", "y": "-34.86", "yaw": "90.0", "z": "1.30" } ] }, "transform": { "pitch": "360.0", "x": "199.66661071777344", "y": "9.503244400024414", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "0", "x": 199.52, "y": 9.7, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "235.71", "y": "-34.55", "yaw": "90.374084", "z": "1.29" }, { "pitch": "0.0", "x": "232.2", "y": "-34.58", "yaw": "90.374084", "z": "1.29" } ] }, "transform": { "pitch": "360.0", "x": "199.5752410888672", "y": "6.001489639282227", "yaw": "0.855804443359375", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "28.78", "y": "196.68", "yaw": "180.072144", "z": "0.99" }, { "pitch": "0.0", "x": "27.30", "y": "193.64", "yaw": "180.072144", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -34.45, "y": 176.76, "yaw": 144.0, "z": 0.99 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "0", "x": 239.96, "y": 98.9, "yaw": 271.0, "z": 1.12 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "234.51", "y": "22.0", "yaw": "91.268036", "z": "2.18" }, { "pitch": "0.0", "x": "231.6", "y": "21.93", "yaw": "91.268036", "z": "2.18" } ], "left": [ { "pitch": "0.0", "x": "201.71", "y": "62.14", "yaw": "1.268036", "z": "2.17" } ] }, "transform": { "pitch": "359.1035461425781", "x": "243.21473693847656", "y": "98.97915649414062", "yaw": "271.3932189941406", "z": "0.29888251423835754" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -85.2, "y": -28.87, "yaw": 89.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-78.1", "y": "41.2", "yaw": "269.486115", "z": "1.3" }, { "pitch": "0.0", "x": "-74.6", "y": "36.80", "yaw": "269.486115", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-41.46", "y": "-3.1", "yaw": "179.103333", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-122.8", "y": "0.83", "yaw": "359.486084", "z": "1.3" } ] }, "transform": { "pitch": "0.8396051526069641", "x": "-88.44371032714844", "y": "-28.86114501953125", "yaw": "89.84374237060547", "z": "-0.26660484075546265" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.36", "y": "-2.95", "yaw": "180.718124", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-85.16", "y": "-33.94", "yaw": "89.683105", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-33.98", "yaw": "90.718109", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-77.98", "y": "39.61", "yaw": "270.218109", "z": "1.38" }, { "pitch": "0.0", "x": "-74.18", "y": "36.65", "yaw": "269.718109", "z": "1.38" } ] }, "transform": { "pitch": "0", "x": -116.67, "y": 0.32, "yaw": 0.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "348.799988", "x": "40.70", "y": "-137.40", "yaw": "180.560562", "z": "3.95" } ], "left": [ { "pitch": "0.0", "x": "0.9", "y": "-173.4", "yaw": "90.437988", "z": "1.0" }, { "pitch": "0.0", "x": "-3.9", "y": "-173.7", "yaw": "91.368103", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "5.65", "y": "-100.19", "yaw": "270.560547", "z": "1.0" }, { "pitch": "0.0", "x": "9.38", "y": "-100.12", "yaw": "272.060516", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -32.34, "y": -135.1, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0", "x": 5.83, "y": -104.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "0.18", "y": "-172.93", "yaw": "90.999603", "z": "1.0" }, { "pitch": "0.0", "x": "-3.12", "y": "-172.99", "yaw": "90.999603", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-37.62", "y": "-135.48", "yaw": "0.999603", "z": "1.16" } ], "right": [ { "pitch": "347.151978", "x": "41.18", "y": "-137.41", "yaw": "180.999588", "z": "3.78" } ] }, "transform": { "pitch": "0.0", "x": "9.106517791748047", "y": "-104.73915100097656", "yaw": "-88.58646392822266", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "1.778076", "x": "-37.55", "y": "-135.41", "yaw": "1.112823", "z": "1.36" } ], "left": [ { "pitch": "359.999237", "x": "5.46", "y": "-100.0", "yaw": "271.128693", "z": "1.19" }, { "pitch": "359.04245", "x": "9.22", "y": "-100.93", "yaw": "271.220764", "z": "1.13" } ], "right": [ { "pitch": "1.071045", "x": "0.11", "y": "-172.88", "yaw": "91.231689", "z": "1.29" }, { "pitch": "1.071045", "x": "-3.18", "y": "-172.95", "yaw": "91.231689", "z": "1.24" } ] }, "transform": { "pitch": "354", "x": 37.76, "y": -137.76, "yaw": 181.0, "z": 3.73 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.6, "y": -167.82, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.51", "y": "-100.51", "yaw": "270.997437", "z": "1.0" }, { "pitch": "0.0", "x": "9.23", "y": "-100.39", "yaw": "270.997437", "z": "1.0" } ], "left": [ { "pitch": "348.837982", "x": "40.97", "y": "-137.39", "yaw": "180.997421", "z": "4.10" } ], "right": [ { "pitch": "0.0", "x": "-37.15", "y": "-135.44", "yaw": "0.997406", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.3387670516967773", "y": "-167.91720581054688", "yaw": "91.41353607177734", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "359", "x": 41.44, "y": -203.9, "yaw": 181.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.095215", "x": "-32.74", "y": "-198.48", "yaw": "1.617889", "z": "0.87" }, { "pitch": "0.095215", "x": "-32.81", "y": "-194.74", "yaw": "1.617889", "z": "0.87" } ], "left": [ { "pitch": "0.0", "x": "7.46", "y": "-163.38", "yaw": "271.617889", "z": "0.94" } ] }, "transform": { "pitch": "0.0", "x": "41.517005920410156", "y": "-206.9641571044922", "yaw": "-178.56045532226562", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "359.91394", "x": "117.78", "y": "-136.11", "yaw": "181.14859", "z": "10.10" } ], "left": [ { "pitch": "4.646606", "x": "83.6", "y": "-166.12", "yaw": "92.100159", "z": "7.73" } ], "right": [ { "pitch": "358.714478", "x": "85.16", "y": "-103.41", "yaw": "271.442688", "z": "9.78" } ] }, "transform": { "pitch": "11", "x": 52.2, "y": -133.34, "yaw": 1.0, "z": 6.48 } }, { "other_actors": { "front": [ { "pitch": "357.548035", "x": "83.78", "y": "-104.47", "yaw": "273.09137", "z": "10.29" } ], "left": [ { "pitch": "359.210297", "x": "117.37", "y": "-135.35", "yaw": "183.091324", "z": "9.81" } ], "right": [ { "pitch": "4.749939", "x": "52.33", "y": "-133.70", "yaw": "1.894897", "z": "7.7" } ] }, "transform": { "pitch": "16", "x": 82.22, "y": -166.54, "yaw": 93.0, "z": 5.3 } }, { "other_actors": { "front": [ { "pitch": "11.270966", "x": "51.93", "y": "-134.6", "yaw": "1.270905", "z": "7.2" } ], "left": [ { "pitch": "0.643555", "x": "85.86", "y": "-103.59", "yaw": "271.270905", "z": "9.73" } ], "right": [ { "pitch": "14.121033", "x": "82.16", "y": "-166.43", "yaw": "91.270874", "z": "5.56" } ] }, "transform": { "pitch": "0", "x": 115.32, "y": -135.69, "yaw": 181.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "83.33", "y": "-166.89", "yaw": "92.13089", "z": "5.98" } ], "left": [ { "pitch": "9.838623", "x": "52.36", "y": "-133.42", "yaw": "2.13089", "z": "6.85" } ], "right": [ { "pitch": "0.0", "x": "115.25", "y": "-136.19", "yaw": "182.130905", "z": "9.35" } ] }, "transform": { "pitch": "0", "x": 84.1, "y": -103.48, "yaw": 272.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "11.675812", "x": "150.78", "y": "-166.9", "yaw": "90.90213", "z": "4.26" } ], "left": [ { "pitch": "359.064728", "x": "119.24", "y": "-132.19", "yaw": "0.90213", "z": "9.53" } ] }, "transform": { "pitch": "0", "x": 153.53, "y": -100.37, "yaw": 270.0, "z": 9.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-46.3", "y": "131.54", "yaw": "179.511353", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.69", "y": "103.97", "yaw": "89.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-88.36", "y": "104.7", "yaw": "89.511353", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-77.11", "y": "165.37", "yaw": "269.511353", "z": "1.0" }, { "pitch": "0.0", "x": "-73.70", "y": "165.55", "yaw": "269.511353", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -117.14, "y": 136.33, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -77.96, "y": 165.64, "yaw": 269.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.96", "y": "100.6", "yaw": "89.67984", "z": "1.0" }, { "pitch": "0.0", "x": "-88.25", "y": "100.7", "yaw": "89.67984", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-116.82", "y": "136.82", "yaw": "359.67984", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-45.81", "y": "131.12", "yaw": "179.67981", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-73.85211944580078", "y": "164.83070373535156", "yaw": "258.85479736328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -84.59, "y": 101.65, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-77.7", "y": "167.18", "yaw": "269.226044", "z": "1.0" }, { "pitch": "0.0", "x": "-73.78", "y": "167.13", "yaw": "269.226044", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-45.48", "y": "131.47", "yaw": "179.226013", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-115.88", "y": "137.58", "yaw": "359.226013", "z": "1.0" } ] }, "transform": { "pitch": "-1.012520670890808", "x": "-88.08773803710938", "y": "101.6595458984375", "yaw": "89.84374237060547", "z": "0.3357953727245331" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-116.9", "y": "137.15", "yaw": "358.753967", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-77.80", "y": "164.23", "yaw": "268.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-73.40", "y": "164.6", "yaw": "268.753967", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.91", "y": "102.90", "yaw": "88.753967", "z": "1.0" }, { "pitch": "0.0", "x": "-88.87", "y": "102.78", "yaw": "88.753967", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -45.5, "y": 131.43, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 2.9, "y": 163.89, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.31", "y": "101.85", "yaw": "90.245483", "z": "1.0" }, { "pitch": "0.0", "x": "-9.74", "y": "102.16", "yaw": "90.245483", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-36.49", "y": "134.69", "yaw": "0.245483", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.57", "y": "130.45", "yaw": "180.245483", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "5.693984508514404", "y": "163.87232971191406", "yaw": "269.637451171875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.12, "y": 102.1, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "2.81", "y": "163.98", "yaw": "269.756226", "z": "1.0" }, { "pitch": "0.0", "x": "6.24", "y": "163.63", "yaw": "269.756226", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.71", "y": "130.88", "yaw": "179.756226", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-38.31", "y": "135.72", "yaw": "359.756195", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-9.697037696838379", "y": "102.12262725830078", "yaw": "89.63746643066406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-36.63", "y": "134.24", "yaw": "359.512756", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "1.94", "y": "163.13", "yaw": "269.512756", "z": "1.0" }, { "pitch": "0.0", "x": "5.61", "y": "163.2", "yaw": "269.512756", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.63", "y": "101.72", "yaw": "89.512695", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "101.54", "yaw": "89.512695", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.39, "y": 130.77, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.55", "y": "130.76", "yaw": "178.835144", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.37", "y": "102.33", "yaw": "88.835144", "z": "1.0" }, { "pitch": "0.0", "x": "-9.4", "y": "102.48", "yaw": "88.835144", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "2.93", "y": "163.65", "yaw": "268.835144", "z": "1.0" }, { "pitch": "0.0", "x": "6.34", "y": "163.79", "yaw": "268.835144", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -37.43, "y": 135.7, "yaw": 358.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-145.36", "y": "31.37", "yaw": "270.062134", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-111.5", "y": "-3.22", "yaw": "180.062134", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -149.26, "y": -29.42, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -77.8, "y": 34.5, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.22", "y": "-34.30", "yaw": "89.490356", "z": "1.3" }, { "pitch": "0.0", "x": "-88.16", "y": "-34.27", "yaw": "89.490356", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-122.3", "y": "0.31", "yaw": "359.490356", "z": "1.3" } ], "right": [ { "pitch": "0.0", "x": "-41.64", "y": "-2.99", "yaw": "180.490356", "z": "1.3" } ] }, "transform": { "pitch": "358.910400390625", "x": "-74.27088165283203", "y": "34.49037170410156", "yaw": "269.84375", "z": "0.18371541798114777" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-122.13", "y": "0.27", "yaw": "0.453156", "z": "1.3" } ], "left": [ { "pitch": "0.0", "x": "-77.72", "y": "39.76", "yaw": "269.523254", "z": "1.30" }, { "pitch": "0.0", "x": "-74.13", "y": "37.13", "yaw": "270.453156", "z": "1.38" } ], "right": [ { "pitch": "0.0", "x": "-85.18", "y": "-33.93", "yaw": "90.453125", "z": "1.3" }, { "pitch": "0.0", "x": "-88.22", "y": "-34.28", "yaw": "90.453125", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": -46.16, "y": -2.92, "yaw": 180.0, "z": 1.3 } } ], "scenario_type": "Scenario8" } ], "Town04": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 97.93, "y": -170.0, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 129.92, "y": -204.42, "yaw": 95.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 160.43, "y": -173.32, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 31.16, "y": -170.4, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 92.43, "y": -173.52, "yaw": 181.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 58.68, "y": -202.99, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 171.23, "y": -307.64, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.15, "y": -341.28, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 233.13, "y": -311.34, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 204.77, "y": -277.61, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -333.24, "y": 435.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-332.98760986328125", "y": "432.04986572265625", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7461853027344", "y": "428.5581970214844", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.5047607421875", "y": "425.0665283203125", "yaw": "3.95513916015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 406.92, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.44630432128906", "y": "403.47784423828125", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.88621520996094", "y": "410.4554138183594", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.60617065429688", "y": "413.9441833496094", "yaw": "175.41065979003906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 173.49, "y": -242.75, "yaw": 353.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 200.9, "y": -276.87, "yaw": 90.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 232.11, "y": -249.54, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 202.96, "y": -216.28, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 226.32, "y": -307.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.82, "y": -276.47, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 287.22, "y": -310.76, "yaw": 181.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 225.69, "y": -246.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 255.26, "y": -278.35, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 286.77, "y": -249.86, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 258.59, "y": -217.4, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 224.3, "y": -169.23, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -183.17, "y": 403.29, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-182.87094116210938", "y": "406.9427185058594", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.58535766601562", "y": "410.4310302734375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.29977416992188", "y": "413.91937255859375", "yaw": "175.3197021484375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -510.3, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-513.669189453125", "y": "92.98770141601562", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6730651855469", "y": "93.22088623046875", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17498779296875", "y": "93.33748626708984", "yaw": "-268.0909423828125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 255.6, "y": -202.61, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -514.1, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1750793457031", "y": "93.2253189086914", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-506.6768493652344", "y": "93.33702087402344", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.17864990234375", "y": "93.44872283935547", "yaw": "-268.1711120605469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -13.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-16.640460968017578", "y": "-230.1665802001953", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.651756286621094", "y": "-229.7690887451172", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.15740442276001", "y": "-229.57032775878906", "yaw": "453.2553405761719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -487.27, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-483.66375732421875", "y": "245.8326873779297", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6600646972656", "y": "246.06027221679688", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1582336425781", "y": "246.17405700683594", "yaw": "268.1368713378906", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -483.59, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.15789794921875", "y": "246.0686798095703", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-490.6559753417969", "y": "246.1850128173828", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1540222167969", "y": "246.30136108398438", "yaw": "268.0950622558594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 287.36, "y": -172.66, "yaw": 179.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 258.49, "y": -138.47, "yaw": 269.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 226.42, "y": -119.8, "yaw": 0.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 254.88, "y": -150.67, "yaw": 90.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 288.3, "y": -121.84, "yaw": 181.0, "z": 1.2 } }, { "transform": { "pitch": "0", "x": 283.7, "y": -246.54, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 311.82, "y": -276.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 344.61, "y": -250.3, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 315.17, "y": -218.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": 282.45, "y": -169.1, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 311.19, "y": -201.37, "yaw": 91.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 342.74, "y": -172.31, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 314.45, "y": -140.51, "yaw": 270.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 281.0, "y": -118.14, "yaw": 0.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 310.66, "y": -148.94, "yaw": 90.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 340.6, "y": -121.2, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 313.89, "y": -89.9, "yaw": 270.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": 321.46, "y": -168.74, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 348.66, "y": -201.48, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 351.31, "y": -136.99, "yaw": 271.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 379.53, "y": -172.9, "yaw": 180.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": -407.46, "y": 26.83, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.4374084472656", "y": "30.340999603271484", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4148864746094", "y": "33.84092712402344", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39239501953125", "y": "37.34085464477539", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -383.23, "y": -19.4, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -407.42, "y": 30.3, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.397216796875", "y": "33.84081268310547", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3747253417969", "y": "37.34074020385742", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4422302246094", "y": "26.840957641601562", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.37, "y": 33.77, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3470153808594", "y": "37.3405647277832", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.39202880859375", "y": "30.340707778930664", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.4145202636719", "y": "26.84078025817871", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -407.33, "y": 37.13, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-407.3511047363281", "y": "33.840518951416016", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3736267089844", "y": "30.34058952331543", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-407.3961181640625", "y": "26.840662002563477", "yaw": "359.631591796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -342.24, "y": 15.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2353210449219", "y": "12.488129615783691", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.23065185546875", "y": "8.98813247680664", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "-0.41707679629325867", "x": "-342.2259521484375", "y": "5.488135814666748", "yaw": "-179.9231719970703", "z": "0.07251979410648346" } }, { "transform": { "pitch": "0", "x": -342.21, "y": 12.51, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2052917480469", "y": "8.988166809082031", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.2005920410156", "y": "5.488170146942139", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "-0.41760769486427307", "x": "-342.21466064453125", "y": "15.988161087036133", "yaw": "-179.9231719970703", "z": "0.07270453125238419" } }, { "transform": { "pitch": "0", "x": -342.18, "y": 9.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1743469238281", "y": "5.488206386566162", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.1837158203125", "y": "12.488200187683105", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "-0.4181567430496216", "x": "-342.18841552734375", "y": "15.988197326660156", "yaw": "-179.9231719970703", "z": "0.0728958398103714" } }, { "transform": { "pitch": "0", "x": -342.15, "y": 5.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.15472412109375", "y": "8.988235473632812", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1593933105469", "y": "12.488232612609863", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "-0.41866618394851685", "x": "-342.1640930175781", "y": "15.988229751586914", "yaw": "-179.9231719970703", "z": "0.07307355850934982" } }, { "transform": { "pitch": "0", "x": -379.68, "y": -18.85, "yaw": 95.0, "z": 1.0 } }, { "transform": { "pitch": "0", "x": -9.69, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.133902549743652", "y": "-230.1801300048828", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.628005981445312", "y": "-230.38319396972656", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.145692825317383", "y": "-229.77401733398438", "yaw": "453.32598876953125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 13.24, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "16.350406646728516", "y": "229.65643310546875", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.356184005737305", "y": "229.37210083007812", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.859072208404541", "y": "229.2299346923828", "yaw": "-87.67208099365234", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.3, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624905586242676", "y": "-79.91557312011719", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.124932289123535", "y": "-79.90184020996094", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624959468841553", "y": "-79.88809967041016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 15.9, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0", "x": 16.8, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.859013557434082", "y": "229.3724365234375", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "9.361806869506836", "y": "229.2326202392578", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.864601135253906", "y": "229.09280395507812", "yaw": "-87.71060180664062", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 432.39, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4604797363281", "y": "435.5253601074219", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.9693603515625", "y": "428.5426025390625", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.7237854003906", "y": "425.0512390136719", "yaw": "4.0231428146362305", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 36.18, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3785705566406", "x": "173.44720458984375", "y": "39.27357482910156", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.56666564941406", "y": "32.274593353271484", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "357.3785705566406", "x": "173.62640380859375", "y": "28.775104522705078", "yaw": "0.9779205322265625", "z": "8.385374069213867" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 34.38, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2730407714844", "x": "6.096894264221191", "y": "37.6077880859375", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.125317096710205", "y": "30.607847213745117", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "360.2730407714844", "x": "6.139528274536133", "y": "27.10787582397461", "yaw": "0.232635498046875", "z": "10.981637954711914" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 34.29, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6138916015625", "y": "37.20619201660156", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60450744628906", "y": "30.206199645996094", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.59982299804688", "y": "26.70620346069336", "yaw": "0.0768280029296875", "z": "5.787003040313721" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 33.53, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.24749755859375", "y": "37.024845123291016", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.2925109863281", "y": "30.02499008178711", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "360.08001708984375", "x": "-358.31500244140625", "y": "26.525062561035156", "yaw": "359.631591796875", "z": "0.0026696426793932915" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 39.53, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.37725830078125", "x": "173.5640869140625", "y": "35.775062561035156", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.6238250732422", "y": "32.275569915771484", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "357.37725830078125", "x": "173.68356323242188", "y": "28.776081085205078", "yaw": "0.9779205322265625", "z": "8.382757186889648" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 37.73, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2725524902344", "x": "6.124706745147705", "y": "34.107872009277344", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.138918399810791", "y": "30.60790252685547", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "360.2725524902344", "x": "6.153129577636719", "y": "27.10793113708496", "yaw": "0.232635498046875", "z": "10.98170280456543" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 37.64, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.60472106933594", "y": "33.70620346069336", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6000213623047", "y": "30.206205368041992", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.5953369140625", "y": "26.706209182739258", "yaw": "0.0768280029296875", "z": "5.787235736846924" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 36.88, "yaw": 359.0, "z": 1.13 } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.2915344238281", "y": "33.52505874633789", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3140563964844", "y": "30.025129318237305", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "360.0795593261719", "x": "-358.3365478515625", "y": "26.52520179748535", "yaw": "359.631591796875", "z": "0.002639642683789134" } }, { "transform": { "pitch": "0", "x": -12.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.358753204345703", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358806610107422", "y": "-75.72421264648438", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.8588337898254395", "y": "-75.73794555664062", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 14.1, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.49053955078125", "y": "10.631532669067383", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.69122314453125", "y": "17.62865447998047", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "1.0338159799575806", "x": "343.79156494140625", "y": "21.127216339111328", "yaw": "178.3571014404297", "z": "0.3580799102783203" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 11.9, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.3455047607422", "y": "7.477066993713379", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.2260284423828", "y": "14.47604751586914", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "2.2167985439300537", "x": "156.16629028320312", "y": "17.97553825378418", "yaw": "-179.02207946777344", "z": "9.130240440368652" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 9.52, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618186950683594", "y": "16.46259880065918", "yaw": "-179.76736450195312", "z": "10.491427421569824" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 9.11, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41539001464844", "y": "5.670230388641357", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42477416992188", "y": "12.6702241897583", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42945861816406", "y": "16.17022132873535", "yaw": "-179.9231719970703", "z": "4.395425319671631" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 10.45, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.70556640625", "y": "14.126648902893066", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.8155212402344", "y": "17.624921798706055", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "1.0299503803253174", "x": "343.92547607421875", "y": "21.123193740844727", "yaw": "178.19967651367188", "z": "0.35540708899497986" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 7.53, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.215087652206421", "x": "156.21119689941406", "y": "10.975284576416016", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.15145874023438", "y": "14.474775314331055", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "2.215087652206421", "x": "156.0917205810547", "y": "17.974266052246094", "yaw": "-179.02207946777344", "z": "9.133125305175781" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 5.96, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.604219436645508", "y": "9.462596893310547", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.618431091308594", "y": "12.962567329406738", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.63264274597168", "y": "16.462539672851562", "yaw": "-179.76736450195312", "z": "10.491179466247559" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 5.55, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4248504638672", "y": "9.170221328735352", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42955017089844", "y": "12.670218467712402", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.43423461914062", "y": "16.170215606689453", "yaw": "-179.9231719970703", "z": "4.395177841186523" } }, { "transform": { "pitch": "0", "x": 385.91, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "382.6264343261719", "y": "-235.0435333251953", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "389.6253967285156", "y": "-235.16390991210938", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1248779296875", "y": "-235.22410583496094", "yaw": "89.01460266113281", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 409.22, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "412.61456298828125", "y": "-85.36454010009766", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61492919921875", "y": "-85.43766784667969", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1151123046875", "y": "-85.47423553466797", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-15.692474365234375", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.6925630569458", "y": "77.76168823242188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192607879638672", "y": "77.74402618408203", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 412.59, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1151123046875", "y": "-85.43630981445312", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "405.61529541015625", "y": "-85.47286987304688", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.115478515625", "y": "-85.50943756103516", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.97, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-13.157381057739258", "y": "-229.76759338378906", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-9.662800788879395", "y": "-229.57290649414062", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-6.168219089508057", "y": "-229.3782196044922", "yaw": "453.188720703125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -16.59, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858835220336914", "y": "-75.72463989257812", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-9.358861923217773", "y": "-75.7383804321289", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858889102935791", "y": "-75.75211334228516", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.94, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192610740661621", "y": "77.7610855102539", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-8.692655563354492", "y": "77.74342346191406", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192700386047363", "y": "77.72576141357422", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 11.74, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.124823570251465", "y": "-79.94327545166016", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.1248779296875", "y": "-79.91580963134766", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624904632568359", "y": "-79.90206909179688", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 12.33, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "15.799628257751465", "y": "76.15249633789062", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "8.79971694946289", "y": "76.18782043457031", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.299761772155762", "y": "76.20548248291016", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 405.54, "y": -85.4, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "409.1143493652344", "y": "-85.36266326904297", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6141662597656", "y": "-85.32609558105469", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "402.1147155761719", "y": "-85.435791015625", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.31, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.858723640441895", "y": "-75.6960678100586", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.35869598388672", "y": "-75.68233489990234", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.858777046203613", "y": "-75.72354125976562", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -8.66, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-12.192425727844238", "y": "77.79782104492188", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692380905151367", "y": "77.81548309326172", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-5.192514896392822", "y": "77.76249694824219", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.4, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "11.624799728393555", "y": "-79.9426498413086", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124772071838379", "y": "-79.95638275146484", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "4.624853134155273", "y": "-79.91517639160156", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 8.63, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "12.299577713012695", "y": "76.15148162841797", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79953384399414", "y": "76.13381958007812", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "5.2996673583984375", "y": "76.18680572509766", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.53, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "12.847021102905273", "y": "229.667236328125", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.34402847290039", "y": "229.8119354248047", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.853006362915039", "y": "229.37783813476562", "yaw": "-87.63053131103516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 428.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.4712219238281", "y": "432.01580810546875", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.721435546875", "y": "435.5068664550781", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-332.97076416015625", "y": "425.0337219238281", "yaw": "4.099803924560547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 410.82, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.47103881835938", "y": "406.9908752441406", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.74537658691406", "y": "403.50164794921875", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-182.92237854003906", "y": "413.9693298339844", "yaw": "175.50453186035156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -506.72, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-510.1669006347656", "y": "92.98015594482422", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.664794921875", "y": "92.85853576660156", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-503.1711120605469", "y": "93.223388671875", "yaw": "-268.00872802734375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -490.77, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-487.16552734375", "y": "245.8351593017578", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.66729736328125", "y": "245.72369384765625", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-494.1619567871094", "y": "246.05809020996094", "yaw": "268.17498779296875", "z": "0.0" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 32.58, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3799743652344", "x": "173.4454803466797", "y": "35.77303695678711", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.38575744628906", "y": "39.272525787353516", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "357.3799743652344", "x": "173.56495666503906", "y": "28.774057388305664", "yaw": "0.9779205322265625", "z": "8.388184547424316" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 30.78, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2735595703125", "x": "6.096487998962402", "y": "34.107757568359375", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.082276821136475", "y": "37.60772705078125", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "360.2735595703125", "x": "6.124910831451416", "y": "27.10781478881836", "yaw": "0.232635498046875", "z": "10.981568336486816" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 30.69, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61404418945312", "y": "33.7061882019043", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6187286376953", "y": "37.20618438720703", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6046600341797", "y": "26.706195831298828", "yaw": "0.0768280029296875", "z": "5.786752700805664" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 29.93, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2468566894531", "y": "33.5247688293457", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.224365234375", "y": "37.024696350097656", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "360.08050537109375", "x": "-358.2918701171875", "y": "26.524913787841797", "yaw": "359.631591796875", "z": "0.002702070167288184" } }, { "transform": { "pitch": "0", "x": 343.59, "y": 17.41, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.5028991699219", "y": "14.132526397705078", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.4099426269531", "y": "10.633761405944824", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "1.0367799997329712", "x": "343.6888732910156", "y": "21.130056381225586", "yaw": "178.47779846191406", "z": "0.3601361811161041" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 14.49, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3299560546875", "y": "10.977312088012695", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.3896942138672", "y": "7.477822303771973", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "2.2178122997283936", "x": "156.21047973632812", "y": "17.976293563842773", "yaw": "-179.02207946777344", "z": "9.12852954864502" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 12.92, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575960159301758", "y": "9.462711334228516", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.561748504638672", "y": "5.962739944458008", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.60438346862793", "y": "16.46265411376953", "yaw": "-179.76736450195312", "z": "10.491663932800293" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 12.51, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41551208496094", "y": "9.170232772827148", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41082763671875", "y": "5.670236110687256", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.42489624023438", "y": "16.17022705078125", "yaw": "-179.9231719970703", "z": "4.3956618309021" } }, { "transform": { "pitch": "0", "x": 389.55, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "386.126953125", "y": "-235.0426788330078", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.62744140625", "y": "-234.98406982421875", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "393.1259765625", "y": "-235.15989685058594", "yaw": "89.04051971435547", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 402.0, "y": -85.4, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "405.6141662597656", "y": "-85.36223602294922", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "409.1139831542969", "y": "-85.32567596435547", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "412.6138000488281", "y": "-85.28910827636719", "yaw": "270.5986022949219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -29.59, "y": 16.5, "yaw": 180.0, "z": 11.43 } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.575634002685547", "y": "12.962740898132324", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.56142234802246", "y": "9.462770462036133", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "-0.9835246801376343", "x": "-29.547210693359375", "y": "5.962799072265625", "yaw": "-179.76736450195312", "z": "10.491913795471191" } }, { "transform": { "pitch": "358", "x": -206.42, "y": 16.9, "yaw": 179.0, "z": 5.36 } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.41432189941406", "y": "12.67023754119873", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.4096221923828", "y": "9.17024040222168", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "-2.9702091217041016", "x": "-206.40493774414062", "y": "5.670243740081787", "yaw": "-179.9231719970703", "z": "4.39596700668335" } }, { "transform": { "pitch": "0", "x": -6.36, "y": -229.98, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-9.628252983093262", "y": "-230.17373657226562", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-13.12211799621582", "y": "-230.38087463378906", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-16.615983963012695", "y": "-230.5880126953125", "yaw": "453.3927917480469", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.98, "y": -75.71, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-9.358698844909668", "y": "-75.69673919677734", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.858672142028809", "y": "-75.68299865722656", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-16.358644485473633", "y": "-75.66926574707031", "yaw": "-270.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.32, "y": 77.78, "yaw": 89.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-8.692384719848633", "y": "77.79701232910156", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-12.192340850830078", "y": "77.8146743774414", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-15.692296028137207", "y": "77.83233642578125", "yaw": "-270.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 4.69, "y": -79.93, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.12476921081543", "y": "-79.9434814453125", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "11.62474250793457", "y": "-79.95721435546875", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.124715805053711", "y": "-79.970947265625", "yaw": "-90.224853515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.29, "y": 76.17, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "8.799537658691406", "y": "76.15229034423828", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "12.299492835998535", "y": "76.13462829589844", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "15.79944896697998", "y": "76.1169662475586", "yaw": "-90.28912353515625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.19, "y": 229.53, "yaw": 269.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "9.344169616699219", "y": "229.6626434326172", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.841078758239746", "y": "229.80970764160156", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "16.337987899780273", "y": "229.95677185058594", "yaw": "-87.59183502197266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -494.19, "y": 245.95, "yaw": 270.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-490.6671142578125", "y": "245.83995056152344", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-487.1688232421875", "y": "245.7306671142578", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-483.6705322265625", "y": "245.6213836669922", "yaw": "268.21075439453125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -503.22, "y": 93.1, "yaw": 90.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-506.6645202636719", "y": "92.97496795654297", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-510.1622009277344", "y": "92.84800720214844", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-513.659912109375", "y": "92.7210464477539", "yaw": "-267.9211730957031", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 393.1, "y": -235.1, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "389.62744140625", "y": "-235.04331970214844", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "386.1278991699219", "y": "-234.98617553710938", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "382.6283874511719", "y": "-234.9290313720703", "yaw": "89.06451416015625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -333.24, "y": 425.47, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-333.46160888671875", "y": "428.5073547363281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.71630859375", "y": "431.9980773925781", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-333.97100830078125", "y": "435.4888000488281", "yaw": "4.173131942749023", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -183.17, "y": 414.14, "yaw": 179.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-183.45127868652344", "y": "410.49993896484375", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.72093200683594", "y": "407.0103454589844", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-183.99057006835938", "y": "403.520751953125", "yaw": "175.5814666748047", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 343.6, "y": 21.0, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.5164794921875", "y": "17.633331298828125", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.4296569824219", "y": "14.134408950805664", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "1.0392494201660156", "x": "343.3428039550781", "y": "10.635486602783203", "yaw": "178.578369140625", "z": "0.36185377836227417" } }, { "transform": { "pitch": "357", "x": 173.5, "y": 29.2, "yaw": 0.0, "z": 9.4 } }, { "transform": { "pitch": "357.3813171386719", "x": "173.4475555419922", "y": "32.272560119628906", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.3878173828125", "y": "35.77205276489258", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "357.3813171386719", "x": "173.32809448242188", "y": "39.271541595458984", "yaw": "0.9779205322265625", "z": "8.39082145690918" } }, { "transform": { "pitch": "2", "x": 326.5, "y": 20.8, "yaw": 180.0, "z": 1.7 } }, { "transform": { "pitch": "1.490559458732605", "x": "326.55828857421875", "y": "17.38355827331543", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6180114746094", "y": "13.88406753540039", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "1.490559458732605", "x": "326.6777648925781", "y": "10.384577751159668", "yaw": "-179.02207946777344", "z": "0.7443756461143494" } }, { "transform": { "pitch": "0", "x": 6.11, "y": 27.4, "yaw": 0.0, "z": 11.96 } }, { "transform": { "pitch": "360.2740478515625", "x": "6.096976280212402", "y": "30.607730865478516", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.082764625549316", "y": "34.10770034790039", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "360.2740478515625", "x": "6.068553447723389", "y": "37.60767364501953", "yaw": "0.232635498046875", "z": "10.981502532958984" } }, { "transform": { "pitch": "2", "x": -179.61, "y": 27.31, "yaw": 359.0, "z": 6.83 } }, { "transform": { "pitch": "362.97021484375", "x": "-179.61387634277344", "y": "30.206186294555664", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.6185760498047", "y": "33.70618438720703", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "362.97021484375", "x": "-179.62326049804688", "y": "37.206180572509766", "yaw": "0.0768280029296875", "z": "5.78651762008667" } }, { "transform": { "pitch": "1", "x": -358.27, "y": 26.55, "yaw": 0.0, "z": 1.13 } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.24761962890625", "y": "30.024702072143555", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.22509765625", "y": "33.52463150024414", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "360.0809631347656", "x": "-358.2026062011719", "y": "37.024559020996094", "yaw": "359.631591796875", "z": "0.0027326939161866903" } }, { "transform": { "pitch": "0", "x": 156.27, "y": 18.7, "yaw": 180.0, "z": 10.31 } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.34207153320312", "y": "14.47802734375", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4018096923828", "y": "10.978536605834961", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "2.2194602489471436", "x": "156.4615478515625", "y": "7.479046821594238", "yaw": "-179.02207946777344", "z": "9.125747680664062" } }, { "transform": { "pitch": "0", "x": 198.95, "y": -199.54, "yaw": 90.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 170.74, "y": -169.54, "yaw": 0.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 204.69, "y": -144.35, "yaw": 263.0, "z": 1.19 } }, { "transform": { "pitch": "0", "x": 229.98, "y": -172.92, "yaw": 180.0, "z": 1.19 } } ], "scenario_type": "Scenario1" } ], "Town05": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 52.73, "y": 145.88, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 55.87, "y": -145.22, "yaw": 0.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 101.5, "y": 137.98, "yaw": 164.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.81, "y": 142.49, "yaw": 344.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 136.31, "y": 121.37, "yaw": 137.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 137.75, "y": 125.7, "yaw": 317.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 149.54, "y": 101.12, "yaw": 107.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 152.94, "y": 104.16, "yaw": 287.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": 49.67, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": 51.39, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.37, "y": 16.76, "yaw": 89.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.55, "y": -16.99, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 151.28, "y": -59.22, "yaw": 88.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 155.5, "y": -57.49, "yaw": 267.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 150.46, "y": -102.24, "yaw": 76.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 154.95, "y": -101.44, "yaw": 255.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 134.58, "y": -127.97, "yaw": 46.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 138.88, "y": -129.5, "yaw": 225.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 98.27, "y": -141.73, "yaw": 11.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 100.88, "y": -145.47, "yaw": 190.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0", "x": -240.52, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.52142333984375", "y": "-76.91566467285156", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.5221405029297", "y": "-76.96470642089844", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.39, "y": 201.6, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-124.4139175415039", "y": "34.73600387573242", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 64.21, "y": 191.24, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.22684478759766", "y": "187.88719177246094", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.19168090820312", "y": "194.88710021972656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 64.28, "y": 194.68, "yaw": 178.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "64.29653930664062", "y": "191.38758850097656", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "64.31412506103516", "y": "187.88763427734375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.7, "y": 204.97, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.9846649169922", "y": "208.22828674316406", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.37538146972656", "y": "201.25485229492188", "yaw": "4.993293762207031", "z": "8.649030685424805" } }, { "transform": { "pitch": "0", "x": -150.41, "y": 208.44, "yaw": 0.0, "z": 9.64 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.1115264892578", "y": "204.78965759277344", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-149.8262939453125", "y": "201.30130004882812", "yaw": "4.674360275268555", "z": "8.643319129943848" } }, { "transform": { "pitch": "0", "x": 203.14, "y": 98.44, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55755615234375", "y": "98.47964477539062", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "210.05731201171875", "y": "98.52024841308594", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 206.79, "y": 98.45, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "210.05767822265625", "y": "98.48790740966797", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0581512451172", "y": "98.40670776367188", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 210.35, "y": 98.46, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "206.55828857421875", "y": "98.416015625", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "203.0585174560547", "y": "98.37541961669922", "yaw": "-89.33536529541016", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 1.26, "y": 187.76, "yaw": 180.0, "z": 1.1 } }, { "transform": { "pitch": "360.0", "x": "1.2433719635009766", "y": "191.07086181640625", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.2257903814315796", "y": "194.57081604003906", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 196.25, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.74073791503906", "y": "-53.869014739990234", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "189.24098205566406", "y": "-53.82814407348633", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 192.54, "y": -53.91, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "189.24046325683594", "y": "-53.87146759033203", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.23997497558594", "y": "-53.953208923339844", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 189.1, "y": -53.9, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "192.7398681640625", "y": "-53.94251251220703", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "196.2396240234375", "y": "-53.98338317871094", "yaw": "89.33090209960938", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -200.24, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.264162540435791", "y": "-203.975341796875", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "1.2039556503295898", "x": "5.249323844909668", "y": "-207.47531127929688", "yaw": "179.75709533691406", "z": "0.052355796098709106" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -204.17, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.199931025505066", "x": "5.265981674194336", "y": "-207.47537231445312", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "1.199931025505066", "x": "5.295659065246582", "y": "-200.47543334960938", "yaw": "179.75709533691406", "z": "0.052006348967552185" } }, { "transform": { "pitch": "0", "x": 5.28, "y": -207.68, "yaw": 180.0, "z": 1.5 } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.295698165893555", "y": "-203.97547912597656", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "1.1963363885879517", "x": "5.310536861419678", "y": "-200.4755096435547", "yaw": "179.75709533691406", "z": "0.05169523134827614" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -193.68, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84249877929688", "y": "-190.1305389404297", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.80551147460938", "y": "-186.6307373046875", "yaw": "359.39447021484375", "z": "10.018385887145996" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -190.18, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.84104919433594", "y": "-186.63034057617188", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91787719726562", "y": "-193.6299285888672", "yaw": "359.3710632324219", "z": "10.018379211425781" } }, { "transform": { "pitch": "0", "x": -140.88, "y": -186.7, "yaw": 0.0, "z": 11.2 } }, { "transform": { "pitch": "360.010498046875", "x": "-140.91917419433594", "y": "-190.1296844482422", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "360.010498046875", "x": "-140.95912170410156", "y": "-193.62945556640625", "yaw": "359.3459167480469", "z": "10.018370628356934" } }, { "transform": { "pitch": "0", "x": -226.86, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1088562011719", "x": "-229.8777618408203", "y": "75.34733581542969", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "360.1088562011719", "x": "-233.37741088867188", "y": "75.29785919189453", "yaw": "270.80999755859375", "z": "9.976667404174805" } }, { "transform": { "pitch": "0", "x": 1.6, "y": 190.79, "yaw": 180.0, "z": 1.23 } }, { "transform": { "pitch": "360.0", "x": "1.6161643266677856", "y": "187.57269287109375", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.5810012817382812", "y": "194.57260131835938", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -229.8, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1090393066406", "x": "-226.3787078857422", "y": "75.43836212158203", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "360.1090393066406", "x": "-233.3780059814453", "y": "75.33940887451172", "yaw": "270.80999755859375", "z": "9.976588249206543" } }, { "transform": { "pitch": "0", "x": -233.43, "y": 75.39, "yaw": 270.0, "z": 11.0 } }, { "transform": { "pitch": "360.1092529296875", "x": "-229.8790740966797", "y": "75.44020080566406", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "360.1092529296875", "x": "-226.37942504882812", "y": "75.48967742919922", "yaw": "270.80999755859375", "z": "9.97649097442627" } }, { "transform": { "pitch": "0", "x": -240.52, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.0202178955078", "y": "-76.80843353271484", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-247.51983642578125", "y": "-76.75688171386719", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -244.3, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-247.52066040039062", "y": "-76.81256103515625", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.52142333984375", "y": "-76.91566467285156", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": -247.63, "y": -76.86, "yaw": 90.0, "z": 11.0 } }, { "transform": { "pitch": "0.0", "x": "-244.02175903320312", "y": "-76.91315460205078", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0.0", "x": "-240.5221405029297", "y": "-76.96470642089844", "yaw": "89.15601348876953", "z": "10.0" } }, { "transform": { "pitch": "0", "x": 1.85, "y": 194.21, "yaw": 180.0, "z": 1.8 } }, { "transform": { "pitch": "360.0", "x": "1.8657550811767578", "y": "191.07398986816406", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "1.8833365440368652", "y": "187.57403564453125", "yaw": "180.28781127929688", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -150.39, "y": 201.6, "yaw": 0.0, "z": 9.65 } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.6641082763672", "y": "204.7429656982422", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "-0.6045733690261841", "x": "-150.96820068359375", "y": "208.229736328125", "yaw": "4.98435640335083", "z": "8.648870468139648" } }, { "transform": { "pitch": "0", "x": 6.52, "y": -190.11, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.08526611328125", "x": "6.53539514541626", "y": "-186.48056030273438", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "359.08526611328125", "x": "6.505717754364014", "y": "-193.48049926757812", "yaw": "359.757080078125", "z": "0.030223362147808075" } }, { "transform": { "pitch": "0", "x": 6.6, "y": -193.56, "yaw": 1.0, "z": 1.0 } }, { "transform": { "pitch": "359.1081237792969", "x": "6.61517858505249", "y": "-189.98094177246094", "yaw": "359.757080078125", "z": "0.028731560334563255" } }, { "transform": { "pitch": "359.1081237792969", "x": "6.630017280578613", "y": "-186.48097229003906", "yaw": "359.757080078125", "z": "0.028731560334563255" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.6", "y": "29.6", "yaw": "268.398804", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "120.28", "y": "2.26", "yaw": "358.398743", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 151.37, "y": -26.18, "yaw": 88.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.13, "y": 187.79, "yaw": 178.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.11193084716797", "y": "191.38665771484375", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-2.93", "y": "202.85", "yaw": "358.756287", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "27.49", "y": "154.53", "yaw": "88.756256", "z": "1.0" }, { "pitch": "0.0", "x": "23.84", "y": "154.74", "yaw": "88.756256", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "64.09435272216797", "y": "194.88661193847656", "yaw": "180.28781127929688", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.65, "y": 158.85, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.19", "y": "187.5", "yaw": "179.153809", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.04859733581543", "y": "158.8513641357422", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.1, "y": 158.8, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.26", "y": "194.61", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.10", "y": "191.9", "yaw": "179.153809", "z": "1.0" }, { "pitch": "0.0", "x": "61.12", "y": "187.21", "yaw": "179.153809", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-2.97", "y": "202.65", "yaw": "359.153748", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.54861831665039", "y": "158.798583984375", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -156.18, "y": -135.51, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.76", "y": "-142.19", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-123.96", "y": "-103.91", "yaw": "270.0", "z": "1.5" }, { "pitch": "0.0", "x": "-120.50", "y": "-103.87", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.15264892578125", "y": "-139.04959106445312", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.99, "y": -138.95, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.23", "y": "-141.87", "yaw": "180.000015", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-124.28", "y": "-103.61", "yaw": "270.0", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-156.0162811279297", "y": "-135.54843139648438", "yaw": "0.44255056977272034", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -120.85, "y": -107.55, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.22", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-124.44915008544922", "y": "-107.5747299194336", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -124.36, "y": -107.3, "yaw": 270.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-159.52", "y": "-138.79", "yaw": "0.208496", "z": "1.5" }, { "pitch": "0.0", "x": "-158.62", "y": "-135.44", "yaw": "0.208496", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-92.11", "y": "-142.5", "yaw": "180.208496", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-120.95111846923828", "y": "-107.2765884399414", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -265.41, "y": 37.0, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.85", "y": "-27.37", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-234.46", "y": "0.13", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-234.57", "y": "-3.77", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-268.8127746582031", "y": "37.034671783447266", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -268.86, "y": 37.1, "yaw": 268.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-272.64", "y": "-32.13", "yaw": "88.359528", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-235.73", "y": "0.3", "yaw": "178.359497", "z": "1.5" }, { "pitch": "0.0", "x": "-235.17", "y": "-3.80", "yaw": "178.359497", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-265.3122863769531", "y": "37.06385040283203", "yaw": "-90.5837631225586", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.36, "y": -3.64, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.3", "y": "37.92", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-266.17", "y": "37.96", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.16", "y": "-36.14", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.70", "y": "-36.19", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.35203552246094", "y": "-0.370522677898407", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -238.41, "y": 0.13, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-269.21", "y": "37.47", "yaw": "270.830933", "z": "1.5" }, { "pitch": "0.0", "x": "-265.76", "y": "37.51", "yaw": "270.830933", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-272.13", "y": "-34.80", "yaw": "90.830902", "z": "1.5" }, { "pitch": "0.0", "x": "-275.75", "y": "-35.52", "yaw": "90.830902", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-238.41973876953125", "y": "-3.870368242263794", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.87, "y": 144.33, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.53", "y": "151.7", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-126.91", "y": "111.56", "yaw": "90.113098", "z": "1.5" }, { "pitch": "0.0", "x": "-131.38", "y": "111.35", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.88619995117188", "y": "147.7713623046875", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -93.88, "y": 147.77, "yaw": 180.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-159.89", "y": "151.11", "yaw": "0.113129", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-127.24", "y": "113.8", "yaw": "90.113098", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-93.86353302001953", "y": "144.2714385986328", "yaw": "-179.7303009033203", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -130.56, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-90.1", "y": "144.39", "yaw": "180.132767", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-127.18934631347656", "y": "115.9299087524414", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -127.5, "y": 115.96, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-89.0", "y": "148.14", "yaw": "180.132767", "z": "1.5" }, { "pitch": "0.0", "x": "-89.0", "y": "144.46", "yaw": "180.132767", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-160.16", "y": "151.73", "yaw": "0.132751", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-130.68896484375", "y": "115.98846435546875", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -190.39, "y": -120.91, "yaw": 91.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.28", "y": "-54.27", "yaw": "271.226715", "z": "1.5" }, { "pitch": "0.0", "x": "-184.54", "y": "-54.21", "yaw": "271.226715", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.99", "y": "-91.4", "yaw": "181.2267", "z": "1.5" }, { "pitch": "0.0", "x": "-152.91", "y": "-94.87", "yaw": "181.2267", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.27", "y": "-88.50", "yaw": "1.226685", "z": "1.5" }, { "pitch": "0.0", "x": "-226.1", "y": "-85.31", "yaw": "1.226685", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-193.41302490234375", "y": "-121.88587951660156", "yaw": "467.89080810546875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.6, "y": -58.77, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.88", "y": "-127.23", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-225.71", "y": "-88.61", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-224.77", "y": "-84.13", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.0", "y": "-92.7", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.5", "y": "-95.85", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-188.08731079101562", "y": "-58.769039154052734", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.24, "y": -91.69, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.54", "y": "-87.83", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-226.52", "y": "-84.10", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-188.57", "y": "-53.51", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.70", "y": "-53.54", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.3", "y": "-125.73", "yaw": "97.322418", "z": "1.5" }, { "pitch": "0.0", "x": "-191.61", "y": "-126.39", "yaw": "96.870911", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.23483276367188", "y": "-95.13064575195312", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -157.26, "y": -95.17, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-224.32", "y": "-87.80", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.71", "y": "-53.3", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.56", "y": "-53.4", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.17", "y": "-126.5", "yaw": "99.915283", "z": "1.5" }, { "pitch": "0.0", "x": "-191.60", "y": "-127.1", "yaw": "96.996216", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-157.26531982421875", "y": "-91.63069152832031", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.83, "y": -88.16, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.54", "y": "-92.11", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-151.56", "y": "-95.85", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.0", "y": "-126.39", "yaw": "98.589478", "z": "1.5" }, { "pitch": "0.0", "x": "-190.91", "y": "-126.31", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.88", "y": "-54.18", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.41", "y": "-53.52", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.83517456054688", "y": "-84.72643280029297", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -193.84, "y": -121.9, "yaw": 92.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.72", "y": "-53.74", "yaw": "268.970154", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-151.70", "y": "-91.96", "yaw": "179.424683", "z": "1.5" }, { "pitch": "0.0", "x": "-151.62", "y": "-95.48", "yaw": "179.510742", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-225.0", "y": "-88.10", "yaw": "0.090057", "z": "1.5" }, { "pitch": "0.0", "x": "-225.89", "y": "-84.55", "yaw": "359.630096", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-190.11427307128906", "y": "-120.71098327636719", "yaw": "467.6999206542969", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.5, "y": -58.73, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.87", "y": "-125.92", "yaw": "94.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-191.29", "y": "-126.41", "yaw": "99.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.44", "y": "-87.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.39", "y": "-84.28", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-154.27", "y": "-91.94", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-153.64", "y": "-95.6", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.58729553222656", "y": "-58.731075286865234", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -220.81, "y": -84.68, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.29", "y": "-92.7", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-186.89", "y": "-126.89", "yaw": "99.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-191.6", "y": "-126.86", "yaw": "99.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.33", "y": "-52.88", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.64", "y": "-52.90", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-220.80465698242188", "y": "-88.22638702392578", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -184.51, "y": 122.92, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-192.23", "y": "51.0", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.89", "y": "91.58", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.85", "y": "95.18", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-152.69", "y": "87.38", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-152.98", "y": "84.10", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-187.46331787109375", "y": "123.50904846191406", "yaw": "258.72021484375", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.51, "y": 87.83, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.49", "y": "91.22", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-227.55", "y": "94.81", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.92", "y": "126.1", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.33", "y": "125.99", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-192.36", "y": "51.31", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-195.73", "y": "51.33", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5060577392578", "y": "84.38876342773438", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.53, "y": 84.35, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-227.50", "y": "91.53", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-187.86", "y": "126.50", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "-184.77", "y": "126.49", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-191.96", "y": "52.27", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "-194.92", "y": "52.53", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-155.5340576171875", "y": "87.88873291015625", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -188.3, "y": 122.96, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.97", "y": "51.1", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-195.56", "y": "50.98", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-226.45", "y": "91.81", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-226.40", "y": "95.60", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-151.77", "y": "87.99", "yaw": "179.302551", "z": "1.5" }, { "pitch": "0.0", "x": "-151.82", "y": "84.46", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-184.14244079589844", "y": "122.22982788085938", "yaw": "260.0389709472656", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -192.1, "y": 57.1, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.37", "y": "126.31", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "-183.86", "y": "126.22", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-153.24", "y": "87.58", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-153.35", "y": "83.71", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-227.86", "y": "92.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-227.77", "y": "95.54", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-195.05535888671875", "y": "57.10081100463867", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -195.57, "y": 57.19, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.13", "y": "126.99", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-152.76", "y": "87.6", "yaw": "178.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-152.86", "y": "83.56", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-226.90", "y": "92.31", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "-226.56", "y": "95.45", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-191.55532836914062", "y": "57.18888854980469", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.8, "y": 91.42, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.62", "y": "87.94", "yaw": "179.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-152.51", "y": "84.35", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.69", "y": "53.20", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.47", "y": "53.23", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-188.34", "y": "127.90", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.81", "y": "127.87", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.80389404296875", "y": "94.8106460571289", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -223.6, "y": 94.9, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-151.85", "y": "87.63", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-191.46", "y": "52.71", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-195.6", "y": "52.73", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "-187.72", "y": "126.93", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "-184.43", "y": "126.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-223.5959014892578", "y": "91.31087493896484", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 98.74, "y": -33.15, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.57", "y": "36.6", "yaw": "268.471954", "z": "1.5" }, { "pitch": "0.0", "x": "106.84", "y": "35.97", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.60", "y": "-2.68", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "65.53", "y": "3.33", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.94", "y": "6.75", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "96.4896011352539", "y": "-33.15665054321289", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 103.3, "y": 33.63, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.62", "y": "-35.65", "yaw": "89.302551", "z": "1.5" }, { "pitch": "0.0", "x": "96.11", "y": "-35.61", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.61", "y": "2.59", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.66", "y": "6.46", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.77", "y": "-2.36", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "106.48635864257812", "y": "33.668888092041016", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.42, "y": 2.5, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.71", "y": "-1.91", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.66", "y": "-36.18", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.34", "y": "-36.15", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.46", "y": "36.1", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.76", "y": "36.67", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.4074935913086", "y": "5.362179279327393", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "65.26", "y": "1.73", "yaw": "359.735962", "z": "1.5" }, { "pitch": "0.0", "x": "65.28", "y": "5.47", "yaw": "359.735962", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "103.23", "y": "36.5", "yaw": "269.735962", "z": "1.5" }, { "pitch": "0.0", "x": "107.10", "y": "36.3", "yaw": "269.735962", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "100.18", "y": "-36.15", "yaw": "89.735931", "z": "1.5" }, { "pitch": "0.0", "x": "96.55", "y": "-36.80", "yaw": "89.735931", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 134.56, "y": -2.13, "yaw": 179.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 95.1, "y": -33.6, "yaw": 88.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "103.10", "y": "36.75", "yaw": "268.471954", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "137.91", "y": "-3.19", "yaw": "178.471924", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "64.4", "y": "2.78", "yaw": "358.471924", "z": "1.5" }, { "pitch": "0.0", "x": "64.15", "y": "6.78", "yaw": "358.471924", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "99.99088287353516", "y": "-33.58554458618164", "yaw": "90.1692886352539", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 107.6, "y": 33.2, "yaw": 269.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "99.88", "y": "-37.52", "yaw": "89.302551", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "64.68", "y": "2.54", "yaw": "359.302551", "z": "1.5" }, { "pitch": "0.0", "x": "64.72", "y": "6.4", "yaw": "359.302551", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "136.45", "y": "-2.34", "yaw": "179.302551", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "102.99250030517578", "y": "33.143775939941406", "yaw": "-89.30083465576172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": 68.39, "y": 5.52, "yaw": 359.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "137.95", "y": "-2.40", "yaw": "179.658813", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "99.74", "y": "-36.67", "yaw": "89.658813", "z": "1.5" }, { "pitch": "0.0", "x": "96.19", "y": "-36.65", "yaw": "89.658813", "z": "1.5" } ], "right": [ { "pitch": "0.0", "x": "103.23", "y": "37.31", "yaw": "269.658813", "z": "1.5" }, { "pitch": "0.0", "x": "106.77", "y": "37.29", "yaw": "269.658813", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "68.40597534179688", "y": "1.8621394634246826", "yaw": "0.2502593994140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": -84.56, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "-91.12", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-126.15", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-131.32", "y": "-126.20", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "-52.11", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.61", "y": "-52.6", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-159.36460876464844", "y": "-88.13385009765625", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.39, "y": -122.45, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.56", "y": "-52.43", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.39", "y": "-122.45", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.34", "y": "-91.68", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-86.87", "y": "-94.84", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.46", "y": "-88.29", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.82", "y": "-84.37", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-127.84723663330078", "y": "-122.4256591796875", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.6, "y": -95.5, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.5", "y": "-88.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.93", "y": "-53.30", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.43", "y": "-53.27", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-128.34", "y": "-127.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-132.34", "y": "-127.36", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.60597229003906", "y": "-91.53479766845703", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.2, "y": -56.45, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.97", "y": "-127.93", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.88", "y": "-87.88", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.91", "y": "-84.38", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.84", "y": "-91.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.80", "y": "-95.12", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-124.8001480102539", "y": "-56.474727630615234", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-36.77", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.73", "y": "3.28", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.77", "y": "6.78", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-88.69", "y": "0.4", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.65", "y": "-3.96", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -121.5, "y": 34.71, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.16, "y": -4.19, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-164.62", "y": "2.74", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.49", "y": "37.56", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.99", "y": "37.59", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.91", "y": "-36.47", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.91", "y": "-36.50", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.15156555175781", "y": "-0.7239478230476379", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -132.2, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.69", "y": "37.42", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.19", "y": "0.33", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-87.11", "y": "-3.63", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-164.10", "y": "2.33", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-164.11", "y": "6.33", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-128.46446228027344", "y": "-32.5643424987793", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.37, "y": 6.36, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-88.18", "y": "0.20", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-127.82", "y": "-35.23", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.32", "y": "-35.28", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-125.14", "y": "38.81", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.61", "y": "38.86", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.37832641601562", "y": "2.9372618198394775", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.35, "y": 56.6, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.1", "y": "126.8", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-54.35", "y": "56.6", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.42", "y": "87.16", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.41", "y": "83.66", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.43", "y": "90.99", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.44", "y": "94.99", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-50.70365524291992", "y": "56.62413787841797", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.91, "y": 94.94, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.85", "y": "87.98", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.53", "y": "52.52", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.38", "y": "52.48", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.25", "y": "126.63", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-46.39", "y": "126.66", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.9060287475586", "y": "91.47069549560547", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.81, "y": 123.1, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.55", "y": "53.23", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.14", "y": "53.33", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.4", "y": "91.56", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.9", "y": "94.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.30", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-12.54", "y": "84.45", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-49.0528450012207", "y": "121.63811492919922", "yaw": "285.5802917480469", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -12.19, "y": 84.49, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.11", "y": "91.33", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.35", "y": "127.83", "yaw": "275.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-46.66", "y": "127.79", "yaw": "275.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.88", "y": "51.37", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.60", "y": "52.25", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-12.194077491760254", "y": "88.05272674560547", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "151.62", "y": "-30.72", "yaw": "88.888824", "z": "1.1" } ], "left": [ { "pitch": "0.0", "x": "120.37", "y": "2.29", "yaw": "358.888824", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 155.9, "y": 25.76, "yaw": 268.0, "z": 1.1 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -120.2, "y": 123.59, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.55", "y": "51.67", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.10", "y": "91.19", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.65", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.12", "y": "87.69", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.64", "y": "84.49", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-123.62055969238281", "y": "123.62052917480469", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.89, "y": 84.45, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-165.80", "y": "91.29", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-123.90", "y": "128.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.76", "y": "128.22", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.63", "y": "51.33", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.75", "y": "50.55", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.89402770996094", "y": "87.96498107910156", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -131.6, "y": 56.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.72", "y": "126.45", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-131.6", "y": "56.43", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.13", "y": "87.53", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.12", "y": "84.3", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-163.14", "y": "91.36", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.15", "y": "95.36", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-127.72073364257812", "y": "56.39537811279297", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.39, "y": 95.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.72", "y": "88.8", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.88", "y": "50.55", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "50.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.53", "y": "127.69", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.82", "y": "127.72", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.38571166992188", "y": "91.38089752197266", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -43.53, "y": 34.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.77", "y": "-36.18", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.42", "y": "3.32", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-85.43", "y": "6.82", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-11.40", "y": "0.41", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-11.39", "y": "-4.41", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.056827545166016", "y": "34.4566535949707", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -15.85, "y": -4.3, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.31", "y": "2.63", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.18", "y": "37.45", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-43.68", "y": "37.48", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.59", "y": "-36.58", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-54.59", "y": "-36.61", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-15.841755867004395", "y": "-0.9121238589286804", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -54.51, "y": -31.74, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.17", "y": "38.28", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.58", "y": "0.64", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-12.58", "y": "-4.14", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-86.59", "y": "3.19", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-86.60", "y": "7.19", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-51.15256881713867", "y": "-31.7597713470459", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -81.92, "y": 6.33, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.22", "y": "0.87", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.37", "y": "-35.26", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.87", "y": "-35.30", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.69", "y": "38.78", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.16", "y": "38.83", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-81.92871856689453", "y": "2.7487454414367676", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -44.38, "y": -56.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.97", "y": "-125.39", "yaw": "67.929413", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-86.93", "y": "-88.66", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-86.35", "y": "-84.84", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.74", "y": "-91.73", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.40", "y": "-95.21", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-47.7984733581543", "y": "-56.53986358642578", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.11, "y": -94.93, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-87.54", "y": "-87.87", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-17.11", "y": "-94.93", "yaw": "180.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.81", "y": "-52.54", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.76", "y": "-52.29", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-61.69", "y": "-124.18", "yaw": "65.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-65.13", "y": "-124.20", "yaw": "65.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.11528968811035", "y": "-91.41958618164062", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -62.5, "y": -120.42, "yaw": 68.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.78", "y": "-53.22", "yaw": "268.054932", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-14.52", "y": "-91.15", "yaw": "180.054916", "z": "1.0" }, { "pitch": "0.0", "x": "-14.46", "y": "-94.54", "yaw": "180.054916", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-87.82", "y": "-88.16", "yaw": "0.054901", "z": "1.0" }, { "pitch": "0.0", "x": "-84.47", "y": "-83.92", "yaw": "0.054901", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-59.20102310180664", "y": "-122.86930084228516", "yaw": "53.40818786621094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.43, "y": -84.43, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-13.51", "y": "-91.6", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.65", "y": "-124.39", "yaw": "66.499481", "z": "0.99" }, { "pitch": "0.0", "x": "-64.47", "y": "-124.44", "yaw": "65.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.36", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.17", "y": "-52.80", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.42459869384766", "y": "-88.01945495605469", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 34.91, "y": 123.61, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.13", "y": "52.90", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.77", "y": "92.18", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.68", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.9", "y": "88.91", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.67", "y": "84.93", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.562679290771484", "y": "123.6086654663086", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 63.0, "y": 84.89, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.99", "y": "92.30", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.67", "y": "126.65", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.17", "y": "126.67", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.26", "y": "52.62", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.26", "y": "52.59", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "63.524505615234375", "y": "87.72471618652344", "yaw": "169.5171356201172", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.63, "y": 55.23, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.53", "y": "127.24", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "24.63", "y": "55.23", "yaw": "90.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.55", "y": "88.89", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.56", "y": "85.10", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.45", "y": "91.17", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.46", "y": "95.61", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "28.089998245239258", "y": "55.231380462646484", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.42, "y": 96.7, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "67.12", "y": "88.3", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.25", "y": "53.83", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.75", "y": "53.86", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.75", "y": "127.81", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.21", "y": "127.78", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.414125442504883", "y": "91.56391906738281", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.12, "y": 33.27, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.35", "y": "-37.44", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.56", "y": "1.84", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.59", "y": "5.34", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.30", "y": "-1.43", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.41", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "31.598772048950195", "y": "33.26858901977539", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.88, "y": -5.25, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-7.11", "y": "2.15", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.54", "y": "36.50", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.4", "y": "36.53", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.13", "y": "-37.53", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.13", "y": "-37.56", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.86433029174805", "y": "-1.6620999574661255", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 24.49, "y": -32.53, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.83", "y": "37.48", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.42", "y": "-1.44", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.42", "y": "-4.94", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-7.59", "y": "2.39", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-7.60", "y": "6.39", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "28.30057144165039", "y": "-32.42808532714844", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.98, "y": 6.4, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.72", "y": "0.55", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.57", "y": "-35.55", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.7", "y": "-35.60", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.25", "y": "38.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "34.78", "y": "38.54", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.9893529415130615", "y": "2.556603193283081", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": 36.11, "y": -56.38, "yaw": 271.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.30", "y": "-127.17", "yaw": "91.368683", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-5.14", "y": "-88.37", "yaw": "1.368683", "z": "0.99" }, { "pitch": "0.0", "x": "-5.22", "y": "-84.87", "yaw": "1.368683", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "66.76", "y": "-90.66", "yaw": "181.368683", "z": "0.99" }, { "pitch": "0.0", "x": "68.40", "y": "-94.62", "yaw": "181.368683", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "32.445068359375", "y": "-56.47802734375", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 65.19, "y": -95.57, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.73", "y": "-87.47", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "33.10", "y": "-53.50", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.37", "y": "-53.51", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.49", "y": "-127.50", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "27.28", "y": "-127.49", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.4598617553711", "y": "-90.88241577148438", "yaw": "-171.14675903320312", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 26.86, "y": -122.64, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "33.28", "y": "-52.53", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.16", "y": "-52.28", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "68.38", "y": "-90.99", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "68.43", "y": "-94.49", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-5.67", "y": "-88.14", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.74", "y": "-84.14", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "30.710643768310547", "y": "-122.5370101928711", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.72, "y": -84.38, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.91", "y": "-91.65", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.42", "y": "-126.27", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.92", "y": "-126.29", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.12", "y": "-52.27", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "36.22", "y": "-52.25", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7252919673919678", "y": "-87.89270782470703", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -184.45, "y": 34.79, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-191.22", "y": "-36.68", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-226.13", "y": "3.36", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-226.17", "y": "6.86", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-152.9", "y": "0.12", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.5", "y": "-3.88", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-188.06150817871094", "y": "34.79099655151367", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -156.0, "y": -4.4, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-228.46", "y": "2.89", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.33", "y": "37.71", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.83", "y": "37.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-191.37", "y": "-36.32", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.94", "y": "-36.2", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-155.9906768798828", "y": "-0.5709943175315857", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -195.4, "y": -31.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-187.71", "y": "39.87", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.12", "y": "0.45", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.11", "y": "-3.95", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-227.13", "y": "3.38", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-227.13", "y": "7.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-191.57980346679688", "y": "-31.551050186157227", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.39, "y": 6.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-153.72", "y": "0.3", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-190.84", "y": "-34.96", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.34", "y": "-35.1", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-188.17", "y": "39.8", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.63", "y": "39.13", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.39862060546875", "y": "3.090656280517578", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "34.66", "y": "169.64", "yaw": "271.585205", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 60.54, "y": 141.67, "yaw": 181.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 35.6, "y": 169.3, "yaw": 269.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "64.64", "y": "141.31", "yaw": "179.831787", "z": "1.3" } ] }, "transform": { "pitch": "0.0", "x": "31.544424057006836", "y": "169.2983856201172", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "37.58", "y": "-116.87", "yaw": "271.097809", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 64.63, "y": -149.58, "yaw": 179.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "0", "x": 37.94, "y": -121.21, "yaw": 271.0, "z": 1.3 } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "68.13", "y": "-148.81", "yaw": "181.798737", "z": "1.3" } ] }, "transform": { "pitch": "360.0", "x": "34.17909240722656", "y": "-121.31058502197266", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 6.44, "y": -186.67, "yaw": 1.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.4259772300720215", "y": "-189.98013305664062", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.36", "y": "-200.93", "yaw": "181.283218", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "34.98", "y": "-151.78", "yaw": "271.283203", "z": "1.0" }, { "pitch": "0.0", "x": "38.98", "y": "-151.81", "yaw": "271.283203", "z": "1.0" } ] }, "transform": { "pitch": "359.0624084472656", "x": "6.411138534545898", "y": "-193.4801025390625", "yaw": "359.757080078125", "z": "0.03175222501158714" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 38.86, "y": -157.24, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "4.36", "y": "-186.70", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.14272689819336", "y": "-157.3394317626953", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 35.42, "y": -157.35, "yaw": 271.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "71.62", "y": "-200.47", "yaw": "181.680908", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "4.45", "y": "-193.56", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.9", "y": "-190.22", "yaw": "1.680908", "z": "1.0" }, { "pitch": "0.0", "x": "4.15", "y": "-186.55", "yaw": "1.680908", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "38.6419563293457", "y": "-157.2638397216797", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "151.22", "y": "-30.42", "yaw": "90.0", "z": "1.1" } ], "right": [ { "pitch": "0.0", "x": "155.36", "y": "29.78", "yaw": "270.0", "z": "1.1" } ] }, "transform": { "pitch": "0", "x": 124.38, "y": 1.52, "yaw": 0.0, "z": 1.1 } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -5.6, "y": 201.85, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.598391056060791", "y": "205.0623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.36", "y": "194.62", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "190.86", "yaw": "180.000015", "z": "1.0" }, { "pitch": "0.0", "x": "61.36", "y": "187.35", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.7", "y": "154.65", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "-0.1941315233707428", "x": "-5.596636772155762", "y": "208.5623321533203", "yaw": "-0.028712520375847816", "z": "0.0014852519379928708" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -271.34, "y": -34.72, "yaw": 90.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-269.34", "y": "34.64", "yaw": "270.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-265.97", "y": "34.69", "yaw": "270.886108", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-233.83", "y": "0.15", "yaw": "180.886108", "z": "1.5" }, { "pitch": "0.0", "x": "-233.78", "y": "-3.69", "yaw": "180.886108", "z": "1.5" } ] }, "transform": { "pitch": "0.0", "x": "-275.5313415527344", "y": "-34.750492095947266", "yaw": "90.41679382324219", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "0", "x": -155.48, "y": 151.3, "yaw": 0.0, "z": 1.5 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.62", "y": "147.91", "yaw": "180.188049", "z": "1.5" }, { "pitch": "0.0", "x": "-89.83", "y": "144.24", "yaw": "180.188049", "z": "1.5" } ], "left": [ { "pitch": "0.0", "x": "-126.55", "y": "112.88", "yaw": "90.188049", "z": "1.5" } ] }, "transform": { "pitch": "360.0", "x": "-155.49497985839844", "y": "154.48143005371094", "yaw": "0.2696990966796875", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -158.84, "y": -88.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.49", "y": "-90.66", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-89.44", "y": "-94.39", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-127.78", "y": "-125.66", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.0", "y": "-125.70", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-124.46", "y": "-53.40", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-52.68", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-158.84552001953125", "y": "-84.63306427001953", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.89, "y": -123.43, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-124.51", "y": "-54.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.78", "y": "-54.10", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-89.93", "y": "-91.84", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-89.93", "y": "-95.71", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.15", "y": "-87.93", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-162.83", "y": "-84.52", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.3402557373047", "y": "-123.45369720458984", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.24, "y": -91.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-162.57", "y": "-88.56", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-162.60", "y": "-84.83", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.4", "y": "-53.77", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.17", "y": "-53.74", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.18", "y": "-125.0", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-130.80", "y": "-126.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.2347412109375", "y": "-95.03424072265625", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.99, "y": -56.48, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.82", "y": "-125.82", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.56", "y": "-125.86", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.71", "y": "-88.37", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.74", "y": "-84.50", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.46", "y": "-91.70", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.74", "y": "-95.44", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-121.30020141601562", "y": "-56.454654693603516", "yaw": "270.3935546875", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -124.87, "y": 35.44, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.70", "y": "-33.90", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.43", "y": "-33.94", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-162.58", "y": "3.55", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-162.61", "y": "7.42", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.33", "y": "0.22", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-89.61", "y": "-3.51", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.90780639648438", "y": "35.40462875366211", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -93.86, "y": 0.69, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-163.19", "y": "2.30", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-163.22", "y": "6.3", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-125.66", "y": "37.9", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-121.79", "y": "37.12", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.80", "y": "-35.14", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.42", "y": "-35.84", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-93.87196350097656", "y": "-4.222204685211182", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -128.53, "y": -32.59, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-125.15", "y": "36.73", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-121.41", "y": "36.74", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-90.56", "y": "0.0", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-90.56", "y": "-4.87", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-162.78", "y": "2.92", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-163.47", "y": "6.32", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-131.96420288085938", "y": "-32.613590240478516", "yaw": "90.39354705810547", "z": "-1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -159.21, "y": 2.86, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-89.86", "y": "0.24", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-89.81", "y": "-3.50", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-128.15", "y": "-34.77", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-131.38", "y": "-34.80", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-124.83", "y": "37.49", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-121.55", "y": "38.21", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-159.20130920410156", "y": "6.436841011047363", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.57, "y": 122.56, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.76", "y": "52.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-54.47", "y": "52.66", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-88.77", "y": "90.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-88.67", "y": "94.83", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.24", "y": "88.26", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.20", "y": "84.39", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-45.82151412963867", "y": "123.0694580078125", "yaw": "286.2447509765625", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -50.85, "y": 56.8, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.96", "y": "127.28", "yaw": "275.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-45.68", "y": "126.92", "yaw": "275.132751", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-12.21", "y": "87.62", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-11.66", "y": "84.60", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-90.2", "y": "91.64", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-89.87", "y": "94.84", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.204750061035156", "y": "56.77779006958008", "yaw": "90.37930297851562", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -83.87, "y": 91.45, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.2", "y": "88.22", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-11.95", "y": "84.75", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-50.91", "y": "52.1", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-53.9", "y": "51.94", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-49.39", "y": "126.51", "yaw": "275.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-45.81", "y": "126.56", "yaw": "275.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-83.87403106689453", "y": "94.97073364257812", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -16.39, "y": 87.98, "yaw": 180.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.72", "y": "90.97", "yaw": "0.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-85.75", "y": "94.71", "yaw": "0.454346", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-49.75", "y": "125.76", "yaw": "279.38501", "z": "0.99" }, { "pitch": "0.0", "x": "-46.84", "y": "125.72", "yaw": "280.454376", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-50.51", "y": "53.54", "yaw": "90.454346", "z": "0.99" }, { "pitch": "0.0", "x": "-54.54", "y": "52.83", "yaw": "90.454346", "z": "0.99" } ] }, "transform": { "pitch": "0.0", "x": "-16.38607406616211", "y": "84.54792785644531", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -123.7, "y": 123.58, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-127.54", "y": "51.5", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-131.5", "y": "51.2", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-167.41", "y": "90.86", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-167.13", "y": "94.32", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-84.67", "y": "87.80", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-84.65", "y": "84.98", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-120.12106323242188", "y": "123.54805755615234", "yaw": "-90.51139068603516", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -88.92, "y": 87.97, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-166.76", "y": "91.4", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-165.71", "y": "94.75", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-124.43", "y": "128.5", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-120.67", "y": "128.3", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-127.68", "y": "50.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-131.1", "y": "50.68", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-88.9159927368164", "y": "84.46495056152344", "yaw": "-179.9344482421875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -127.56, "y": 56.11, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-123.92", "y": "128.11", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-120.29", "y": "128.45", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-85.18", "y": "88.34", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-84.63", "y": "85.24", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-166.73", "y": "91.68", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-166.58", "y": "94.87", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-131.22312927246094", "y": "56.142696380615234", "yaw": "89.48860931396484", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -162.35, "y": 91.63, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-84.15", "y": "88.3", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-84.11", "y": "84.76", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-126.79", "y": "51.43", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-130.83", "y": "51.38", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-123.86", "y": "127.87", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-120.49", "y": "127.91", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-162.35372924804688", "y": "94.88094329833984", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.3, "y": 34.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-50.31", "y": "-35.26", "yaw": "90.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-54.5", "y": "-35.27", "yaw": "90.209442", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-84.95", "y": "2.42", "yaw": "0.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-84.96", "y": "6.29", "yaw": "0.209442", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-12.72", "y": "-1.38", "yaw": "180.209442", "z": "1.0" }, { "pitch": "0.0", "x": "-12.3", "y": "-5.13", "yaw": "180.209442", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-43.557861328125", "y": "34.62477111816406", "yaw": "270.3793029785156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -16.15, "y": 0.81, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-85.48", "y": "2.18", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-85.51", "y": "5.92", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-47.95", "y": "36.98", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.8", "y": "37.0", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-50.9", "y": "-35.25", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-53.71", "y": "-35.96", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-16.16270637512207", "y": "-4.41135311126709", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -51.1, "y": -32.19, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "37.13", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-43.90", "y": "37.14", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-13.5", "y": "0.60", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-13.5", "y": "-4.47", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.27", "y": "3.31", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-85.96", "y": "6.72", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-54.6550407409668", "y": "-32.16905975341797", "yaw": "89.66251373291016", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -82.15, "y": 2.83, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.79", "y": "0.61", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-12.74", "y": "-4.29", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-51.9", "y": "-34.80", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-54.32", "y": "-34.83", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-47.77", "y": "37.47", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-44.49", "y": "38.18", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-82.14167785644531", "y": "6.249274253845215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -47.88, "y": -56.6, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-60.61", "y": "-124.17", "yaw": "68.35498", "z": "1.0" }, { "pitch": "0.0", "x": "-64.72", "y": "-124.21", "yaw": "66.757843", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-87.13", "y": "-88.14", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-87.21", "y": "-84.49", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-14.61", "y": "-91.63", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-14.71", "y": "-95.13", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-44.298892974853516", "y": "-56.62109375", "yaw": "269.6625061035156", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -17.14, "y": -91.43, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-90.32", "y": "-87.99", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-88.31", "y": "-84.48", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-48.32", "y": "-52.38", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-44.32", "y": "-52.35", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-60.43", "y": "-124.42", "yaw": "67.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-64.42", "y": "-124.45", "yaw": "67.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-17.134746551513672", "y": "-94.91961669921875", "yaw": "-179.9136962890625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -58.23, "y": -120.96, "yaw": 72.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-47.64", "y": "-51.0", "yaw": "269.106506", "z": "1.0" }, { "pitch": "0.0", "x": "-43.84", "y": "-51.90", "yaw": "269.106506", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-16.52", "y": "-91.17", "yaw": "180.106522", "z": "1.0" }, { "pitch": "0.0", "x": "-15.29", "y": "-94.53", "yaw": "180.106522", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-85.8", "y": "-88.9", "yaw": "359.106476", "z": "1.0" }, { "pitch": "0.0", "x": "-85.41", "y": "-84.44", "yaw": "359.106476", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-60.89959716796875", "y": "-119.1965560913086", "yaw": "56.552635192871094", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -83.39, "y": -87.93, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-16.53", "y": "-91.60", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "-16.49", "y": "-94.87", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "-60.82", "y": "-124.23", "yaw": "65.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-63.92", "y": "-124.27", "yaw": "68.105591", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "-48.29", "y": "-52.59", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "-44.70", "y": "-52.55", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-83.3951416015625", "y": "-84.5194091796875", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.41, "y": 123.81, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.58", "y": "54.47", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "24.84", "y": "54.43", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.30", "y": "91.92", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.33", "y": "95.79", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "65.95", "y": "88.59", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.66", "y": "84.85", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.062599182128906", "y": "123.81145477294922", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.5, "y": 88.39, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.83", "y": "91.38", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.86", "y": "95.12", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "31.65", "y": "126.18", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "35.13", "y": "126.21", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.56", "y": "53.94", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "24.94", "y": "53.24", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "61.875518798828125", "y": "84.45710754394531", "yaw": "170.9776611328125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 28.13, "y": 56.9, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.51", "y": "126.22", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.24", "y": "126.23", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "66.9", "y": "88.49", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "66.10", "y": "84.62", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.13", "y": "92.40", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.81", "y": "95.81", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "24.589330673217773", "y": "56.89858627319336", "yaw": "90.02288818359375", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.78, "y": 91.79, "yaw": 359.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.50", "y": "87.72", "yaw": "179.553589", "z": "0.99" }, { "pitch": "0.0", "x": "66.47", "y": "83.98", "yaw": "179.553589", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "27.49", "y": "53.52", "yaw": "89.553589", "z": "0.99" }, { "pitch": "0.0", "x": "24.26", "y": "53.55", "yaw": "89.553589", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.60", "y": "126.72", "yaw": "269.553589", "z": "0.99" }, { "pitch": "0.0", "x": "35.62", "y": "126.68", "yaw": "269.553589", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.7837445735931396", "y": "95.0634994506836", "yaw": "0.0655517578125", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 31.63, "y": 33.82, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "28.80", "y": "-35.52", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "25.6", "y": "-35.56", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-6.9", "y": "1.93", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-6.12", "y": "5.80", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "66.16", "y": "-1.40", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "66.88", "y": "-5.14", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "35.09855270385742", "y": "33.82138442993164", "yaw": "-89.97711181640625", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 62.71, "y": -1.48, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.64", "y": "2.51", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-6.66", "y": "5.77", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "30.91", "y": "36.31", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "34.78", "y": "36.33", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.77", "y": "-35.92", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "25.14", "y": "-36.63", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "62.72608184814453", "y": "-5.1627373695373535", "yaw": "-179.74974060058594", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 27.99, "y": -32.52, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.36", "y": "36.79", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "35.10", "y": "36.80", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "65.95", "y": "0.94", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "65.95", "y": "-4.81", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-6.27", "y": "2.98", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-6.96", "y": "6.38", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "24.804058074951172", "y": "-32.6052131652832", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "0", "x": -2.66, "y": 1.61, "yaw": 0.0, "z": 0.99 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.69", "y": "-1.2", "yaw": "180.75441", "z": "0.99" }, { "pitch": "0.0", "x": "66.74", "y": "-4.75", "yaw": "180.75441", "z": "0.99" } ], "left": [ { "pitch": "0.0", "x": "28.40", "y": "-36.2", "yaw": "90.754395", "z": "0.99" }, { "pitch": "0.0", "x": "25.17", "y": "-36.6", "yaw": "90.754395", "z": "0.99" } ], "right": [ { "pitch": "0.0", "x": "31.72", "y": "36.24", "yaw": "270.754395", "z": "0.99" }, { "pitch": "0.0", "x": "35.0", "y": "36.96", "yaw": "270.754395", "z": "0.99" } ] }, "transform": { "pitch": "360.0", "x": "-2.649179220199585", "y": "6.055785655975342", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 32.71, "y": -56.24, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "30.49", "y": "-125.57", "yaw": "90.552979", "z": "1.0" }, { "pitch": "0.0", "x": "27.0", "y": "-125.61", "yaw": "90.552979", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-5.2", "y": "-88.11", "yaw": "0.552979", "z": "1.0" }, { "pitch": "0.0", "x": "-5.5", "y": "-84.24", "yaw": "0.552979", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.23", "y": "-91.48", "yaw": "180.552979", "z": "1.0" }, { "pitch": "0.0", "x": "67.94", "y": "-95.22", "yaw": "180.552979", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "35.937644958496094", "y": "-56.1536750793457", "yaw": "271.5320739746094", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 64.38, "y": -91.4, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.92", "y": "-87.73", "yaw": "359.888672", "z": "1.0" }, { "pitch": "0.0", "x": "-4.91", "y": "-83.99", "yaw": "359.888672", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "32.96", "y": "-53.30", "yaw": "269.888672", "z": "1.0" }, { "pitch": "0.0", "x": "36.83", "y": "-53.32", "yaw": "269.888672", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "30.10", "y": "-125.51", "yaw": "89.888641", "z": "1.0" }, { "pitch": "0.0", "x": "26.47", "y": "-126.18", "yaw": "89.888641", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "64.83172607421875", "y": "-94.36640930175781", "yaw": "-171.34144592285156", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 30.36, "y": -122.55, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "32.83", "y": "-53.19", "yaw": "270.885925", "z": "1.0" }, { "pitch": "0.0", "x": "36.56", "y": "-53.14", "yaw": "270.885925", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "67.90", "y": "-90.47", "yaw": "180.885925", "z": "1.0" }, { "pitch": "0.0", "x": "67.96", "y": "-94.34", "yaw": "180.885925", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-4.36", "y": "-87.50", "yaw": "0.885895", "z": "1.0" }, { "pitch": "0.0", "x": "-5.9", "y": "-84.11", "yaw": "0.885895", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "27.211990356445312", "y": "-122.63420104980469", "yaw": "91.5320816040039", "z": "1.52587890625e-05" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 0.71, "y": -87.87, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "68.62", "y": "-91.18", "yaw": "180.188705", "z": "1.0" }, { "pitch": "0.0", "x": "68.63", "y": "-94.92", "yaw": "180.188705", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "29.98", "y": "-125.81", "yaw": "90.18869", "z": "1.0" }, { "pitch": "0.0", "x": "26.76", "y": "-125.81", "yaw": "90.18869", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "32.64", "y": "-53.59", "yaw": "270.18869", "z": "1.0" }, { "pitch": "0.0", "x": "35.76", "y": "-52.90", "yaw": "270.18869", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "0.7047622799873352", "y": "-84.39273834228516", "yaw": "0.0863037109375", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -187.95, "y": 34.76, "yaw": 270.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-190.78", "y": "-34.59", "yaw": "90.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.63", "yaw": "90.586456", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-225.66", "y": "2.87", "yaw": "0.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-225.69", "y": "6.74", "yaw": "0.586456", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-153.41", "y": "0.47", "yaw": "180.586456", "z": "1.0" }, { "pitch": "0.0", "x": "-152.70", "y": "-4.20", "yaw": "180.586456", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-184.5615234375", "y": "34.75906753540039", "yaw": "-90.01580047607422", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -157.3, "y": 0.55, "yaw": 180.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-226.37", "y": "2.44", "yaw": "0.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-226.40", "y": "6.18", "yaw": "0.454346", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-188.83", "y": "37.24", "yaw": "270.454376", "z": "1.0" }, { "pitch": "0.0", "x": "-184.96", "y": "37.26", "yaw": "270.454376", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-190.97", "y": "-34.99", "yaw": "90.454346", "z": "1.0" }, { "pitch": "0.0", "x": "-194.59", "y": "-35.70", "yaw": "90.454346", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-157.3112335205078", "y": "-4.067790508270264", "yaw": "179.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -191.55, "y": -31.54, "yaw": 90.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-188.17", "y": "37.78", "yaw": "270.132782", "z": "1.0" }, { "pitch": "0.0", "x": "-184.43", "y": "37.79", "yaw": "270.132782", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-153.58", "y": "0.5", "yaw": "180.132767", "z": "1.0" }, { "pitch": "0.0", "x": "-153.58", "y": "-3.82", "yaw": "180.132767", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-225.80", "y": "2.60", "yaw": "0.132751", "z": "1.0" }, { "pitch": "0.0", "x": "-226.49", "y": "6.22", "yaw": "0.132751", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-195.07980346679688", "y": "-31.539026260375977", "yaw": "89.98419952392578", "z": "0.055450439453125" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -222.35, "y": 3.13, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-152.99", "y": "0.50", "yaw": "180.75441", "z": "1.0" }, { "pitch": "0.0", "x": "-152.95", "y": "-3.23", "yaw": "180.75441", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "-191.28", "y": "-34.50", "yaw": "90.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-194.51", "y": "-34.54", "yaw": "90.754395", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-187.96", "y": "37.76", "yaw": "270.754395", "z": "1.0" }, { "pitch": "0.0", "x": "-184.68", "y": "38.48", "yaw": "270.754395", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-222.34158325195312", "y": "6.5905280113220215", "yaw": "359.86053466796875", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 69.14, "y": -200.75, "yaw": 179.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.12518310546875", "y": "-204.24607849121094", "yaw": "179.75709533691406", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "3.30", "y": "-193.55", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.31", "y": "-190.4", "yaw": "359.88678", "z": "1.0" }, { "pitch": "0.0", "x": "3.32", "y": "-186.26", "yaw": "359.88678", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "35.18", "y": "-151.96", "yaw": "269.88678", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "69.11034393310547", "y": "-207.7460479736328", "yaw": "179.75709533691406", "z": "0.0" } } ], "scenario_type": "Scenario8" } ], "Town06": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 669.39, "y": 83.38, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "672.7225952148438", "y": "83.4161376953125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7229614257812", "y": "83.34022521972656", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2232055664062", "y": "83.30226135253906", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.723388671875", "y": "83.2643051147461", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.7, "y": 83.5, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.2218627929688", "y": "83.46227264404297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.7220458984375", "y": "83.42431640625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2222900390625", "y": "83.3863525390625", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7224731445312", "y": "83.34839630126953", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -5.3, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-8.675992965698242", "y": "-53.622528076171875", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -9.0, "y": -53.6, "yaw": 90.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-5.176236152648926", "y": "-53.574485778808594", "yaw": "90.3823013305664", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 2.4, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "5.828932285308838", "y": "20.622880935668945", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.9, "y": 20.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "2.3291661739349365", "y": "20.576173782348633", "yaw": "270.3822937011719", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -16.7, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-20.065515518188477", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.5749969482422", "y": "-23.56549072265625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-13.065561294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -20.2, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58773803710938", "y": "-23.56553840637207", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6132354736328", "y": "-16.565584182739258", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.6259765625", "y": "-13.065608024597168", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -23.8, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.6136016845703", "y": "-20.065608978271484", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.62635803222656", "y": "-16.565631866455078", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.63909912109375", "y": "-13.065655708312988", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -12.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187618255615234", "y": "-16.09782600402832", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.174869537353516", "y": "-19.597803115844727", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -16.1, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.187252044677734", "y": "-19.597848892211914", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.212745666503906", "y": "-12.597894668579102", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.91, "y": 41.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.90859985351562", "y": "45.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9071807861328", "y": "48.9715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.90577697753906", "y": "52.4715690612793", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.92, "y": 45.38, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.91854858398438", "y": "48.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.91714477539062", "y": "52.47157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.92138671875", "y": "41.97157669067383", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 48.98, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9285888671875", "y": "52.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93141174316406", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.93283081054688", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -178.93, "y": 52.88, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-178.9315643310547", "y": "48.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9329833984375", "y": "45.471580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-178.9344024658203", "y": "41.971580505371094", "yaw": "-0.023140989243984222", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 44.2, "y": -19.7, "yaw": 179.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "44.21311569213867", "y": "-16.097919464111328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "44.225860595703125", "y": "-12.597942352294922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 658.6, "y": 82.95, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "662.2265625", "y": "82.98932647705078", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "665.726318359375", "y": "83.02729034423828", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2261352539062", "y": "83.06524658203125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7259521484375", "y": "83.10320281982422", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 662.3, "y": 83.6, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "665.7197265625", "y": "83.63709259033203", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "669.2195434570312", "y": "83.675048828125", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7193603515625", "y": "83.71300506591797", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7201538085938", "y": "83.56117248535156", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.8, "y": 83.17, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "669.224609375", "y": "83.20713806152344", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "672.7244262695312", "y": "83.2450942993164", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "662.2250366210938", "y": "83.13121795654297", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "658.7252197265625", "y": "83.09326171875", "yaw": "270.62139892578125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 9.4, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "12.778694152832031", "y": "276.646728515625", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "5.77956485748291", "y": "276.75714111328125", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 239.9, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.6988410949707", "y": "243.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68668746948242", "y": "246.61331176757812", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.674537658691406", "y": "250.11329650878906", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -10.2, "y": 213.5, "yaw": 89.0, "z": 1.0 } }, { "transform": { "pitch": "360.0", "x": "-6.720656394958496", "y": "213.4451141357422", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-3.2210917472839355", "y": "213.38990783691406", "yaw": "89.09619140625", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6298828125", "y": "138.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6454467773438", "y": "138.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 657.7, "y": 183.15, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "661.1398315429688", "y": "183.1873016357422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6395874023438", "y": "183.2252655029297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.139404296875", "y": "183.2632293701172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6392211914062", "y": "183.30117797851562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 661.7, "y": 183.26, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "664.6388549804688", "y": "183.2918701171875", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "668.138671875", "y": "183.329833984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6384887695312", "y": "183.36778259277344", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6392822265625", "y": "183.21595764160156", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "626.658935546875", "y": "138.49703979492188", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 665.2, "y": 183.37, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.137939453125", "y": "183.40187072753906", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "671.6377563476562", "y": "183.4398193359375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1383666992188", "y": "183.32594299316406", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6385498046875", "y": "183.28799438476562", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 668.99, "y": 183.58, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "671.6359252929688", "y": "183.60870361328125", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6362915039062", "y": "183.5327911376953", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1365356445312", "y": "183.4948272705078", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.63671875", "y": "183.45687866210938", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 672.3, "y": 183.7, "yaw": 270.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "668.1351928710938", "y": "183.6548309326172", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "664.6353759765625", "y": "183.6168670654297", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "661.1356201171875", "y": "183.5789031982422", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "657.6358032226562", "y": "183.54095458984375", "yaw": "-89.37859344482422", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -35.7, "y": 250.5, "yaw": 359.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "-35.71349334716797", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.72564697265625", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-35.737796783447266", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 172.6, "y": -13.4, "yaw": 180.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "172.58847045898438", "y": "-16.565494537353516", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.57571411132812", "y": "-20.065471649169922", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "172.56297302246094", "y": "-23.565448760986328", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 5.6, "y": 276.7, "yaw": 269.0, "z": 1.0 } }, { "transform": { "pitch": "0.0", "x": "9.278183937072754", "y": "276.6419982910156", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "12.777749061584473", "y": "276.5867919921875", "yaw": "-90.90380859375", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3915710449219", "y": "45.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3932800292969", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39495849609375", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3915100097656", "y": "48.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3931884765625", "y": "52.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3880920410156", "y": "41.74409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3863830566406", "y": "38.24409866333008", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.39154052734375", "y": "52.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3881530761719", "y": "45.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3864440917969", "y": "41.744102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3847351074219", "y": "38.244102478027344", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 52.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.27813720703125", "y": "48.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27642822265625", "y": "45.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27471923828125", "y": "41.74415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.27301025390625", "y": "38.24415588378906", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.4, "y": 138.59, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.39260864257812", "y": "135.4395294189453", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.49070739746094", "y": "138.93931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.48249816894531", "y": "135.43931579589844", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -239.6, "y": 240.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-239.59410095214844", "y": "243.68092346191406", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58779907226562", "y": "247.180908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-239.58151245117188", "y": "250.680908203125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -359.5, "y": 58.1, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-362.68389892578125", "y": "57.73311233520508", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-366.160888671875", "y": "57.33245086669922", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.63787841796875", "y": "56.931793212890625", "yaw": "96.57328033447266", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -13.9, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.298583984375", "y": "-17.034290313720703", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28582763671875", "y": "-20.53426742553711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.2731018066406", "y": "-24.034242630004883", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 503.51, "y": -10.4, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "503.5177307128906", "y": "-13.939313888549805", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5253601074219", "y": "-17.439306259155273", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.53302001953125", "y": "-20.93929672241211", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "503.5406494140625", "y": "-24.439289093017578", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 38.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.401611328125", "y": "41.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.405029296875", "y": "48.74409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4067077636719", "y": "52.24409484863281", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 38.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.40155029296875", "y": "41.81858444213867", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40325927734375", "y": "45.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40496826171875", "y": "48.818580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40667724609375", "y": "52.318580627441406", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 41.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29331970214844", "y": "45.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29661560058594", "y": "48.73708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29991149902344", "y": "52.23708724975586", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.4, "y": 138.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3869323730469", "y": "141.3854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3725891113281", "y": "144.8854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3582458496094", "y": "148.38539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3439025878906", "y": "151.88536071777344", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.4, "y": 137.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3870544433594", "y": "140.75856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3727111816406", "y": "144.25852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3583679199219", "y": "147.7584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3440246582031", "y": "151.2584686279297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.3, "y": 136.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "140.13125610351562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2720184326172", "y": "143.6312255859375", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.25767517089844", "y": "147.13119506835938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2433319091797", "y": "150.63116455078125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.1, "y": 135.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 333.2, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1989440917969", "y": "241.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.19775390625", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.196533203125", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1953430175781", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 237.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89891052246094", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89772033691406", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8965301513672", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.8953399658203", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 238.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09896469116211", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09777069091797", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.096576690673828", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.095382690429688", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": 301.31, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2978210449219", "y": "-20.534311294555664", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.28509521484375", "y": "-24.034286499023438", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3233337402344", "y": "-13.534357070922852", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.31, "y": -20.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.2974853515625", "y": "-24.034332275390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3229675292969", "y": "-17.034378051757812", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.3357238769531", "y": "-13.534401893615723", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.89, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.886695861816406", "y": "48.880615234375", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.883399963378906", "y": "45.380619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.880104064941406", "y": "41.880619049072266", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993091583251953", "y": "52.38051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98649787902832", "y": "45.380523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.98320198059082", "y": "41.880523681640625", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.99, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "18.993099212646484", "y": "48.880516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.996397018432617", "y": "52.380516052246094", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "18.986507415771484", "y": "41.88051986694336", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.15, "y": -24.1, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.143310546875", "y": "-21.04495620727539", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1356506347656", "y": "-17.544963836669922", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1280212402344", "y": "-14.04497241973877", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.120361328125", "y": "-10.544981002807617", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.3, "y": -20.6, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.30859375", "y": "-24.54460334777832", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2933044433594", "y": "-17.544620513916016", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2856750488281", "y": "-14.044628143310547", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.27801513671875", "y": "-10.544636726379395", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 455.2, "y": -17.2, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "455.2084045410156", "y": "-21.04481315612793", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.2160339355469", "y": "-24.5448055267334", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.193115234375", "y": "-14.044830322265625", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "455.1854553222656", "y": "-10.544838905334473", "yaw": "-179.87489318847656", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "48.737091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.29624938964844", "y": "52.237091064453125", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "41.73709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 49.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.29295349121094", "y": "52.23709487915039", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28636169433594", "y": "45.237098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.28306579589844", "y": "41.737098693847656", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.19, "y": 52.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.1865692138672", "y": "48.73719024658203", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1832733154297", "y": "45.2371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.1799774169922", "y": "41.7371940612793", "yaw": "-0.053955771028995514", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 608.5, "y": -23.7, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "608.475830078125", "y": "-20.404850006103516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4502563476562", "y": "-16.904943466186523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.4246215820312", "y": "-13.405036926269531", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "608.3989868164062", "y": "-9.905130386352539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.93, "y": -20.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9571533203125", "y": "-23.908740997314453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9059448242188", "y": "-16.90892791748047", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8803100585938", "y": "-13.409022331237793", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8546752929688", "y": "-9.9091157913208", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.92, "y": -16.8, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9463500976562", "y": "-20.40872573852539", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9719848632812", "y": "-23.90863037109375", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8951416015625", "y": "-13.408912658691406", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8695068359375", "y": "-9.909006118774414", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 607.91, "y": -13.2, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "607.9371337890625", "y": "-16.90869903564453", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9627075195312", "y": "-20.408605575561523", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.9883422851562", "y": "-23.908512115478516", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "607.8858642578125", "y": "-9.908886909484863", "yaw": "180.41941833496094", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 42.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "48.81858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.39501953125", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3882141113281", "y": "38.367977142333984", "yaw": "-1.1906731128692627", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 45.59, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3916015625", "y": "48.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.393310546875", "y": "52.3185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38818359375", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3865051269531", "y": "38.36801528930664", "yaw": "-1.191046118736267", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 49.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.39154052734375", "y": "52.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38812255859375", "y": "45.31858825683594", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.38641357421875", "y": "41.8185920715332", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3847351074219", "y": "38.36804962158203", "yaw": "-1.191433072090149", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 52.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.2782287597656", "y": "48.818641662597656", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2765197753906", "y": "45.31864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.2748107910156", "y": "41.81864547729492", "yaw": "-0.02789534069597721", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.27313232421875", "y": "38.370391845703125", "yaw": "-1.2159260511398315", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 142.1, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37860107421875", "y": "144.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3642578125", "y": "148.3854217529297", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.34991455078125", "y": "151.88539123535156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40728759765625", "y": "137.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 145.69, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.37896728515625", "y": "148.38548278808594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3646240234375", "y": "151.8854522705078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.40765380859375", "y": "141.3855438232422", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4219970703125", "y": "137.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.39, "y": 149.2, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.3789978027344", "y": "151.88551330566406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4076843261719", "y": "144.8855743408203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4220275878906", "y": "141.38560485839844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.4363708496094", "y": "137.88563537597656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 477.28, "y": 152.49, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "477.29681396484375", "y": "148.38514709472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.3111572265625", "y": "144.8851776123047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.32550048828125", "y": "141.3852081298828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "477.33984375", "y": "137.88523864746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.28, "y": 151.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.29693603515625", "y": "147.7582550048828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.311279296875", "y": "144.25828552246094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.32562255859375", "y": "140.75831604003906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3399658203125", "y": "137.2583465576172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 148.6, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.3791198730469", "y": "151.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4078063964844", "y": "144.25868225097656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4221496582031", "y": "140.7587127685547", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4364929199219", "y": "137.2587432861328", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 145.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.38238525390625", "y": "147.75860595703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3680419921875", "y": "151.25857543945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.41107177734375", "y": "140.7586669921875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.4254150390625", "y": "137.25869750976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 324.39, "y": 141.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "324.37872314453125", "y": "144.25856018066406", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.3643798828125", "y": "147.75852966308594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.35003662109375", "y": "151.2584991455078", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "324.40740966796875", "y": "137.2586212158203", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 18.7, "y": 139.79, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.5, "y": 143.39, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 18.3, "y": 146.89, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 17.91, "y": 150.19, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 26.1, "y": 241.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.099102020263672", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09790802001953", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09671401977539", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.101490020751953", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 245.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "248.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.09794044494629", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.1, "y": 249.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.09913444519043", "y": "251.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10152244567871", "y": "244.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.10271644592285", "y": "241.03451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.103910446166992", "y": "237.53451538085938", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 26.0, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "26.001453399658203", "y": "248.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.002647399902344", "y": "244.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.003841400146484", "y": "241.03448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "26.005035400390625", "y": "237.53448486328125", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990478515625", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89785766601562", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89666748046875", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.89907836914062", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.89788818359375", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90145874023438", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.8990936279297", "y": "251.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90147399902344", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026641845703", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90386962890625", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 178.9, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "178.9014434814453", "y": "248.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.9026336669922", "y": "244.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.90382385253906", "y": "241.08665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "178.905029296875", "y": "237.58665466308594", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 241.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "244.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978454589844", "y": "248.1392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1966552734375", "y": "251.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2014465332031", "y": "237.6392822265625", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 245.4, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.1978759765625", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 248.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.1990661621094", "y": "251.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20147705078125", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2026672363281", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.203857421875", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 333.2, "y": 252.3, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "333.201416015625", "y": "248.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20263671875", "y": "244.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.2038269042969", "y": "241.13929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "333.20501708984375", "y": "237.63929748535156", "yaw": "0.019545903429389", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.4069061279297", "y": "247.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41319274902344", "y": "243.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41949462890625", "y": "240.06185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.42579650878906", "y": "236.56185913085938", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.3944854736328", "y": "250.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40707397460938", "y": "243.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.4133758544922", "y": "240.0618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.419677734375", "y": "236.5618438720703", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -173.4, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-173.39450073242188", "y": "247.0618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.38819885253906", "y": "250.5618133544922", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.40708923339844", "y": "240.06182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-173.41339111328125", "y": "236.56182861328125", "yaw": "-0.10308279097080231", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.3, "y": 135.19, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.31700897216797", "y": "142.43972778320312", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.3252182006836", "y": "145.93971252441406", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.40902709960938", "y": "142.43951416015625", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-85.417236328125", "y": "145.9394989013672", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -85.5, "y": 142.9, "yaw": 180.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-85.50712585449219", "y": "145.9392852783203", "yaw": "180.13438415527344", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -15.6, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.913684844970703", "y": "-19.357091903686523", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.8881893157959", "y": "-12.357137680053711", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -21.9, "y": -18.0, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-21.892196655273438", "y": "-15.857145309448242", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-21.87944793701172", "y": "-12.357169151306152", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -20.99, "y": -22.5, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0", "x": 171.19, "y": 151.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2095489501953", "y": "147.13099670410156", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.22389221191406", "y": "143.6310272216797", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2382354736328", "y": "140.1310577392578", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.2525634765625", "y": "136.63108825683594", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 147.8, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.2783966064453", "y": "150.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3070831298828", "y": "143.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.32142639160156", "y": "140.1313934326172", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.33575439453125", "y": "136.6314239501953", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 144.29, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27835083007812", "y": "147.1312713623047", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26400756835938", "y": "150.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30703735351562", "y": "140.13133239746094", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.3213653564453", "y": "136.63136291503906", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 171.29, "y": 140.7, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "171.27798461914062", "y": "143.63124084472656", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.26364135742188", "y": "147.13121032714844", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.24929809570312", "y": "150.6311798095703", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "171.30665588378906", "y": "136.6313018798828", "yaw": "0.23475661873817444", "z": "0.0" } }, { "transform": { "pitch": "0", "x": 301.41, "y": -24.1, "yaw": 179.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "301.4229736328125", "y": "-20.534767150878906", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.43572998046875", "y": "-17.0347900390625", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "301.448486328125", "y": "-13.534812927246094", "yaw": "179.79132080078125", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 250.9, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.4670104980469", "y": "247.23248291015625", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3401794433594", "y": "243.7347869873047", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.2133483886719", "y": "240.23707580566406", "yaw": "2.0767877101898193", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 247.5, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.720947265625", "y": "250.7255096435547", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.45867919921875", "y": "243.73043823242188", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.3275451660156", "y": "240.23289489746094", "yaw": "2.147228479385376", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -308.6, "y": 244.0, "yaw": 0.0, "z": 1.9 } }, { "transform": { "pitch": "0.0", "x": "-308.7252197265625", "y": "247.22280883789062", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.861083984375", "y": "250.7201690673828", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0.0", "x": "-308.4534606933594", "y": "240.22808837890625", "yaw": "2.2249090671539307", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -369.0, "y": 58.46, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.3059387207031", "y": "58.7149658203125", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.8215026855469", "y": "59.044734954833984", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3370666503906", "y": "59.37450408935547", "yaw": "95.40641784667969", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -366.61, "y": 58.44, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-369.7657470703125", "y": "58.129947662353516", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-362.7992858886719", "y": "58.81438446044922", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.3160705566406", "y": "59.1566047668457", "yaw": "95.61116790771484", "z": "0.0" } }, { "transform": { "pitch": "0", "x": -363.11, "y": 58.42, "yaw": 89.0, "z": 1.9 } }, { "transform": { "pitch": "360.0", "x": "-366.2443542480469", "y": "58.09443664550781", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-369.72564697265625", "y": "57.73284912109375", "yaw": "95.92984771728516", "z": "0.0" } }, { "transform": { "pitch": "360.0", "x": "-359.2818298339844", "y": "58.81761169433594", "yaw": "95.92984771728516", "z": "0.0" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 37.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0021362304688", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0038452148438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0055541992188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0072631835938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 41.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0053100585938", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 44.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0018920898438", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0036010742188", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984741210938", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967651367188", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 48.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "627.0017700195312", "y": "52.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9983520507812", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9966430664062", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949340820312", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 627.0, "y": 51.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9984130859375", "y": "48.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9967041015625", "y": "45.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9949951171875", "y": "41.671260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "658.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "665.0", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.50", "y": "86.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "672.0", "y": "86.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.9932861328125", "y": "38.171260833740234", "yaw": "-0.027896113693714142", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.71, "y": 243.29, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.698463439941406", "y": "246.6133575439453", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.68631362915039", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.65", "y": "208.21", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.15", "y": "208.25", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.7227668762207", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5847778320312", "y": "141.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5704345703125", "y": "145.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5560913085938", "y": "148.9967041015625", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5418090820312", "y": "152.49667358398438", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 142.3, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "145.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.572509765625", "y": "148.99676513671875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5582275390625", "y": "152.49673461914062", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 246.7, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.688148498535156", "y": "250.11334228515625", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71245193481445", "y": "243.11338806152344", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-6.69", "y": "208.32", "yaw": "89.27478", "z": "1.0" }, { "pitch": "0.0", "x": "-10.19", "y": "208.37", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "239.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -35.7, "y": 250.2, "yaw": 359.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.71244812011719", "y": "246.6134033203125", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.72460174560547", "y": "243.11343383789062", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-10.30", "y": "208.77", "yaw": "89.27478", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "-35.736751556396484", "y": "239.6134490966797", "yaw": "-0.19892168045043945", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 145.8, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5868530273438", "y": "148.996826171875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.5725708007812", "y": "152.49679565429688", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6155395507812", "y": "141.99688720703125", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 149.6, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.588134765625", "y": "152.49685668945312", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6167602539062", "y": "145.49691772460938", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.631103515625", "y": "141.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": 626.6, "y": 152.9, "yaw": 0.0, "z": 1.0 } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6159057617188", "y": "148.9969482421875", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6302490234375", "y": "145.49697875976562", "yaw": "0.23475661873817444", "z": "0.0" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "657.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "661.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "664.60", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "668.10", "y": "187.80", "yaw": "270.0", "z": "1.0" }, { "pitch": "0.0", "x": "671.60", "y": "187.80", "yaw": "270.0", "z": "1.0" } ] }, "transform": { "pitch": "0.0", "x": "626.6445922851562", "y": "141.99700927734375", "yaw": "0.23475661873817444", "z": "0.0" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -3.1, "y": 213.55, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-6.7181010246276855", "y": "213.60708618164062", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.75", "y": "283.52", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.25", "y": "283.51", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.75", "y": "283.50", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.91", "y": "239.51", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.90", "y": "243.5", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.217665672302246", "y": "213.66229248046875", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": -6.8, "y": 213.52, "yaw": 89.0, "z": 1.0 } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-10.219058990478516", "y": "213.57394409179688", "yaw": "89.09619140625", "z": "0.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "5.95", "y": "283.48", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "9.45", "y": "283.46", "yaw": "269.792236", "z": "1.0" }, { "pitch": "0.0", "x": "12.95", "y": "283.45", "yaw": "269.792236", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "-39.71", "y": "239.64", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.70", "y": "243.14", "yaw": "359.792206", "z": "1.0" }, { "pitch": "0.0", "x": "-39.69", "y": "246.64", "yaw": "359.792206", "z": "1.0" } ] }, "transform": { "pitch": "360.0", "x": "-3.2199301719665527", "y": "213.46353149414062", "yaw": "89.09619140625", "z": "0.0" } } ], "scenario_type": "Scenario8" } ], "Town08": [ { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "31.20", "y": "220.60", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "33.90", "y": "105.70", "yaw": "1", "z": "0.98" } }, { "transform": { "pitch": "359", "x": "64.50", "y": "135.80", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "359", "x": "89.20", "y": "106.18", "yaw": "181", "z": "0.98" } }, { "transform": { "pitch": "0", "x": "61.10", "y": "76.70", "yaw": "91", "z": "0.87" } }, { "transform": { "pitch": "0", "x": "33.90", "y": "44.60", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "64.60", "y": "74.70", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "60.60", "y": "13.10", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "31.10", "y": "41.10", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-45.90", "y": "44.30", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "0.40", "y": "76.30", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "86.80", "y": "216.90", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-3.90", "y": "76.30", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-13.84", "y": "12.66", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-10.34", "y": "12.69", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-2.0", "y": "192.40", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-5.50", "y": "192.40", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-16.31", "y": "187.39", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-12.80", "y": "187.40", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-2.81", "y": "252.12", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-6.30", "y": "252.10", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-50.50", "y": "220.40", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "60.60", "y": "188.60", "yaw": "92", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "31.0", "y": "217.20", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-15.10", "y": "120.37", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-11.70", "y": "120.39", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-41.80", "y": "145.71", "yaw": "32", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "31.40", "y": "158.10", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-1.10", "y": "133.50", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "30.40", "y": "101.80", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "73.50", "y": "161.40", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "73.90", "y": "109.30", "yaw": "1", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "118.40", "y": "29.20", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "114.90", "y": "29.30", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "99.30", "y": "76.39", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "102.80", "y": "76.30", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "99.30", "y": "127.59", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "102.80", "y": "127.50", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "98.40", "y": "186.69", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "101.90", "y": "186.60", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "117.30", "y": "192.20", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "113.80", "y": "192.30", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "65.20", "y": "245.30", "yaw": "262", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "70.70", "y": "220.60", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "117.60", "y": "141.30", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "114.10", "y": "141.40", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-44.24", "y": "-28.21", "yaw": "359", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-44.30", "y": "-31.70", "yaw": "359", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "0.50", "y": "2.50", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-3.0", "y": "2.50", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-13.30", "y": "257.80", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-95.40", "y": "140.40", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-91.80", "y": "151.50", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-64.30", "y": "153.10", "yaw": "135", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-71.70", "y": "165.90", "yaw": "315", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-64.73", "y": "126.61", "yaw": "213", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-94.90", "y": "73.8", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "155.90", "y": "78.10", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "156.40", "y": "129.29", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "156.70", "y": "186.10", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "130.29", "y": "220.60", "yaw": "359", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "148.39", "y": "216.99", "yaw": "179", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "129.70", "y": "161.30", "yaw": "359", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "33.20", "y": "161.40", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "129.70", "y": "110.10", "yaw": "359", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "160.0", "y": "141.30", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "160.0", "y": "192.90", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "14.59", "y": "-38.4", "yaw": "1", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "29.10", "y": "292.30", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "14.40", "y": "-34.34", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "14.41", "y": "-30.84", "yaw": "1", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "14.41", "y": "-27.14", "yaw": "0", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "197.59", "y": "-4.26", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "194.10", "y": "-4.30", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "89.40", "y": "157.80", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "190.60", "y": "-4.30", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "187.30", "y": "-4.30", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "198.9", "y": "126.67", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "194.60", "y": "126.60", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "190.90", "y": "126.60", "yaw": "89", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "187.40", "y": "126.59", "yaw": "90", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "171.18", "y": "299.56", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "170.90", "y": "295.90", "yaw": "179", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "170.89", "y": "292.40", "yaw": "179", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "170.90", "y": "288.90", "yaw": "180", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "64.40", "y": "189.60", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-156.69", "y": "223.60", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-153.60", "y": "223.82", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-150.10", "y": "223.81", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "-146.60", "y": "223.80", "yaw": "269", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "144.89", "y": "106.59", "yaw": "179", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "159.71", "y": "246.60", "yaw": "270", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "70.69", "y": "1.48", "yaw": "354", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "143.92", "y": "-2.60", "yaw": "187", "z": "1.10" } }, { "transform": { "pitch": "0", "x": "11.88", "y": "105.4", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "60.79", "y": "63.67", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "103.30", "y": "62.48", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-15.7", "y": "127.49", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-14.30", "y": "76.77", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "114.40", "y": "62.48", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "11.88", "y": "161.32", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "103.30", "y": "31.85", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-13.21", "y": "253.22", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-58.26", "y": "43.81", "yaw": "0", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "-10.70", "y": "76.77", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-15.73", "y": "188.87", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "118.19", "y": "91.50", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-61.56", "y": "221.7", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "18.84", "y": "44.53", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "146.53", "y": "253.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.61", "y": "253.45", "yaw": "0", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "47.82", "y": "157.74", "yaw": "180", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "47.82", "y": "102.27", "yaw": "180", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "92.52", "y": "253.87", "yaw": "0", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "47.82", "y": "217.10", "yaw": "180", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "64.71", "y": "144.81", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "99.3", "y": "120.96", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "11.27", "y": "220.95", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "0.34", "y": "81.0", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "102.72", "y": "172.61", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-11.47", "y": "127.49", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-16.81", "y": "253.22", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-1.11", "y": "131.71", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "102.72", "y": "120.96", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "60.91", "y": "119.15", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "146.53", "y": "250.8", "yaw": "179", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "99.51", "y": "31.85", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-4.71", "y": "131.71", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-6.45", "y": "257.45", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "47.8", "y": "40.99", "yaw": "179", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "118.19", "y": "62.48", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "99.51", "y": "62.48", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-3.94", "y": "81.0", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-61.56", "y": "217.38", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "64.38", "y": "86.48", "yaw": "269", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "98.83", "y": "172.61", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-12.13", "y": "188.87", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.77", "y": "193.9", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "114.40", "y": "91.50", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-2.85", "y": "257.45", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-37.48", "y": "40.69", "yaw": "175", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "-5.37", "y": "193.9", "yaw": "270", "z": "0.99" } } ], "scenario_type": "Scenario1" }, { "available_event_configurations": [ { "transform": { "pitch": "0", "x": "11.88", "y": "105.4", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "60.79", "y": "63.67", "yaw": "89", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.61", "y": "250.8", "yaw": "179", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "103.30", "y": "62.48", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-15.7", "y": "127.49", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-14.30", "y": "76.77", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "114.40", "y": "62.48", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "11.88", "y": "161.32", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "103.30", "y": "31.85", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-13.21", "y": "253.22", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-58.26", "y": "43.81", "yaw": "0", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "-10.70", "y": "76.77", "yaw": "90", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-15.73", "y": "188.87", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "118.19", "y": "91.50", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-61.56", "y": "221.7", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "18.84", "y": "44.53", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "92.52", "y": "250.8", "yaw": "179", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "146.53", "y": "253.54", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "121.61", "y": "253.45", "yaw": "0", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "47.82", "y": "157.74", "yaw": "180", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "47.82", "y": "102.27", "yaw": "180", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "92.52", "y": "253.87", "yaw": "0", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "47.82", "y": "217.10", "yaw": "180", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "64.71", "y": "144.81", "yaw": "270", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "99.3", "y": "120.96", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "11.27", "y": "220.95", "yaw": "0", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "0.34", "y": "81.0", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "102.72", "y": "172.61", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-11.47", "y": "127.49", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.11", "y": "131.71", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "102.72", "y": "120.96", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "60.91", "y": "119.15", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "146.53", "y": "250.8", "yaw": "179", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "99.51", "y": "31.85", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-4.71", "y": "131.71", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-6.45", "y": "257.45", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "47.8", "y": "40.99", "yaw": "179", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "118.19", "y": "62.48", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "99.51", "y": "62.48", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-3.94", "y": "81.0", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-61.56", "y": "217.38", "yaw": "180", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "64.38", "y": "86.48", "yaw": "269", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "98.83", "y": "172.61", "yaw": "90", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-12.13", "y": "188.87", "yaw": "90", "z": "1.0" } }, { "transform": { "pitch": "0", "x": "-1.77", "y": "193.9", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "114.40", "y": "91.50", "yaw": "270", "z": "1.21" } }, { "transform": { "pitch": "0", "x": "-2.85", "y": "257.45", "yaw": "270", "z": "0.99" } }, { "transform": { "pitch": "0", "x": "-37.48", "y": "40.69", "yaw": "175", "z": "1.15" } }, { "transform": { "pitch": "0", "x": "-5.37", "y": "193.9", "yaw": "270", "z": "0.99" } } ], "scenario_type": "Scenario3" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "0.0", "x": "86.20", "y": "217.10", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "60.57", "y": "186.81", "yaw": "91.672546", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "67.8", "y": "247.91", "yaw": "257.175415", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "31.20", "y": "220.60", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "359.996063", "x": "88.17", "y": "105.94", "yaw": "181.318146", "z": "0.98" } ], "left": [ { "pitch": "0.222626", "x": "60.98", "y": "72.54", "yaw": "91.318146", "z": "0.85" } ], "right": [ { "pitch": "359.777374", "x": "64.37", "y": "138.24", "yaw": "271.318146", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "33.90", "y": "105.70", "yaw": "1", "z": "0.98" } }, { "other_actors": { "front": [ { "pitch": "0.222656", "x": "60.73", "y": "72.75", "yaw": "90.305206", "z": "0.85" } ], "left": [ { "pitch": "0.0", "x": "29.18", "y": "106.1", "yaw": "0.305206", "z": "0.98" } ], "right": [ { "pitch": "0.0", "x": "87.90", "y": "105.64", "yaw": "180.305206", "z": "0.98" } ] }, "transform": { "pitch": "359", "x": "64.50", "y": "135.80", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.003937", "x": "29.19", "y": "105.80", "yaw": "1.317993", "z": "0.98" } ], "left": [ { "pitch": "359.777374", "x": "64.63", "y": "139.3", "yaw": "271.318024", "z": "1.11" } ], "right": [ { "pitch": "0.222626", "x": "60.86", "y": "72.41", "yaw": "91.317993", "z": "0.85" } ] }, "transform": { "pitch": "359", "x": "89.20", "y": "106.18", "yaw": "181", "z": "0.98" } }, { "other_actors": { "front": [ { "pitch": "359.777374", "x": "64.30", "y": "138.55", "yaw": "271.317871", "z": "1.11" } ], "left": [ { "pitch": "359.996063", "x": "88.38", "y": "106.13", "yaw": "181.317856", "z": "0.98" } ], "right": [ { "pitch": "0.003937", "x": "30.41", "y": "106.0", "yaw": "1.317841", "z": "0.98" } ] }, "transform": { "pitch": "0", "x": "61.10", "y": "76.70", "yaw": "91", "z": "0.87" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "61.11", "y": "7.93", "yaw": "90.078583", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "64.86", "y": "77.51", "yaw": "270.078613", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "33.90", "y": "44.60", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.44", "y": "7.36", "yaw": "89.977997", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "32.15", "y": "44.74", "yaw": "359.977997", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "64.60", "y": "74.70", "yaw": "269", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "64.58", "y": "77.5", "yaw": "269.318359", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "32.20", "y": "44.79", "yaw": "359.318329", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "60.60", "y": "13.10", "yaw": "89", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-45.91", "y": "43.99", "yaw": "0.078491", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-3.95", "y": "76.5", "yaw": "270.078491", "z": "1.10" }, { "pitch": "0.0", "x": "0.61", "y": "76.5", "yaw": "270.078491", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-9.0", "y": "9.4", "yaw": "90.078461", "z": "1.10" }, { "pitch": "0.0", "x": "-13.89", "y": "9.3", "yaw": "90.078461", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "31.10", "y": "41.10", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.10", "y": "41.40", "yaw": "180.078644", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-10.17", "y": "9.34", "yaw": "90.078613", "z": "1.10" }, { "pitch": "0.0", "x": "-13.86", "y": "9.34", "yaw": "90.078613", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-3.95", "y": "76.35", "yaw": "270.078613", "z": "1.10" }, { "pitch": "0.0", "x": "0.45", "y": "76.36", "yaw": "270.078613", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-45.90", "y": "44.30", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-10.31", "y": "7.99", "yaw": "90.078583", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-44.96", "y": "43.73", "yaw": "0.078583", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "31.58", "y": "40.84", "yaw": "180.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "0.40", "y": "76.30", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-10.15", "y": "7.97", "yaw": "90.078583", "z": "1.10" }, { "pitch": "0.0", "x": "-14.7", "y": "8.20", "yaw": "90.078583", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-45.40", "y": "43.74", "yaw": "0.078583", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "31.78", "y": "40.84", "yaw": "180.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-3.90", "y": "76.30", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.15", "y": "76.27", "yaw": "270.618195", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "31.34", "y": "40.65", "yaw": "180.618195", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-44.25", "y": "43.84", "yaw": "0.618164", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-13.84", "y": "12.66", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.20", "y": "76.26", "yaw": "270.618195", "z": "1.10" }, { "pitch": "0.0", "x": "0.50", "y": "76.30", "yaw": "270.618195", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "31.36", "y": "40.65", "yaw": "180.618195", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-44.30", "y": "43.83", "yaw": "0.618164", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-10.34", "y": "12.69", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.47", "y": "119.38", "yaw": "90.078766", "z": "1.10" }, { "pitch": "0.0", "x": "-14.85", "y": "119.38", "yaw": "90.078766", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "36.56", "y": "158.27", "yaw": "180.078751", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-41.89", "y": "145.98", "yaw": "33.054169", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-2.0", "y": "192.40", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.52", "y": "119.39", "yaw": "90.078583", "z": "1.10" }, { "pitch": "0.0", "x": "-14.77", "y": "119.38", "yaw": "91.766205", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-41.75", "y": "145.36", "yaw": "34.068298", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "35.91", "y": "158.20", "yaw": "180.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-5.50", "y": "192.40", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.29", "y": "252.41", "yaw": "270.078827", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "28.28", "y": "216.94", "yaw": "180.078812", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-49.8", "y": "220.85", "yaw": "0.078796", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-16.31", "y": "187.39", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "252.40", "yaw": "270.078827", "z": "1.10" }, { "pitch": "0.0", "x": "-3.16", "y": "252.41", "yaw": "270.078827", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "28.77", "y": "216.93", "yaw": "180.078812", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-49.9", "y": "220.85", "yaw": "0.078796", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-12.80", "y": "187.40", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.63", "y": "187.3", "yaw": "90.502686", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-49.36", "y": "220.71", "yaw": "0.502686", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "27.51", "y": "216.85", "yaw": "180.502686", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-2.81", "y": "252.12", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.85", "y": "187.4", "yaw": "90.502686", "z": "1.10" }, { "pitch": "0.0", "x": "-16.41", "y": "187.0", "yaw": "90.502686", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-49.72", "y": "220.71", "yaw": "0.502686", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "28.82", "y": "216.87", "yaw": "180.502686", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-6.30", "y": "252.10", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "29.53", "y": "217.10", "yaw": "180.502945", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-12.92", "y": "187.72", "yaw": "90.502899", "z": "1.10" }, { "pitch": "0.0", "x": "-16.2", "y": "187.70", "yaw": "90.502899", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-6.33", "y": "249.93", "yaw": "270.50293", "z": "1.10" }, { "pitch": "0.0", "x": "-3.18", "y": "250.10", "yaw": "270.50293", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-50.50", "y": "220.40", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "66.82", "y": "247.76", "yaw": "257.621796", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "86.64", "y": "217.28", "yaw": "182.760468", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "28.14", "y": "220.50", "yaw": "2.515625", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "60.60", "y": "188.60", "yaw": "92", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.4", "y": "220.49", "yaw": "0.502808", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-6.59", "y": "249.87", "yaw": "270.502838", "z": "1.10" }, { "pitch": "0.0", "x": "-3.49", "y": "249.89", "yaw": "270.502838", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-12.50", "y": "187.76", "yaw": "90.502777", "z": "1.10" }, { "pitch": "0.0", "x": "-16.18", "y": "187.73", "yaw": "90.502777", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "31.0", "y": "217.20", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-5.66", "y": "193.13", "yaw": "270.529999", "z": "1.10" }, { "pitch": "0.0", "x": "-2.4", "y": "193.16", "yaw": "270.529999", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "36.13", "y": "158.19", "yaw": "180.529984", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-40.91", "y": "145.50", "yaw": "35.733582", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-15.10", "y": "120.37", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-5.74", "y": "193.45", "yaw": "270.529999", "z": "1.10" }, { "pitch": "0.0", "x": "-2.19", "y": "193.49", "yaw": "270.529999", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "36.69", "y": "158.0", "yaw": "180.529984", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-41.67", "y": "145.65", "yaw": "35.881683", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-11.70", "y": "120.39", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "37.5", "y": "158.71", "yaw": "181.3517", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-12.29", "y": "122.23", "yaw": "88.502625", "z": "1.10" }, { "pitch": "0.0", "x": "-14.96", "y": "121.11", "yaw": "90.477356", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-5.41", "y": "191.12", "yaw": "271.922607", "z": "1.10" }, { "pitch": "0.0", "x": "-2.14", "y": "192.27", "yaw": "271.895691", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-41.80", "y": "145.71", "yaw": "32", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.66", "y": "145.74", "yaw": "34.578308", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-5.57", "y": "192.64", "yaw": "270.078796", "z": "1.10" }, { "pitch": "0.0", "x": "-2.14", "y": "192.64", "yaw": "270.078796", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-11.82", "y": "120.8", "yaw": "90.078735", "z": "1.10" }, { "pitch": "0.0", "x": "-14.95", "y": "120.0", "yaw": "90.078735", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "31.40", "y": "158.10", "yaw": "180", "z": "1.10" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "34.86", "y": "101.98", "yaw": "180.078751", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-1.10", "y": "133.50", "yaw": "270", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-1.59", "y": "138.22", "yaw": "270.078796", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "30.40", "y": "101.80", "yaw": "180", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "102.30", "y": "126.90", "yaw": "90.0", "z": "1.10" }, { "pitch": "0.0", "x": "99.2", "y": "126.90", "yaw": "90.0", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "73.50", "y": "161.40", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "148.99", "y": "106.64", "yaw": "181.318146", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "103.3", "y": "76.35", "yaw": "91.318115", "z": "1.10" }, { "pitch": "0.0", "x": "99.31", "y": "76.28", "yaw": "91.318115", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "114.31", "y": "143.85", "yaw": "271.318115", "z": "1.10" }, { "pitch": "0.0", "x": "117.86", "y": "143.94", "yaw": "271.318115", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "73.90", "y": "109.30", "yaw": "1", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "72.18", "y": "1.5", "yaw": "357.1297", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "118.40", "y": "29.20", "yaw": "270", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "71.79", "y": "0.73", "yaw": "357.430969", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "142.20", "y": "-2.79", "yaw": "184.920807", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "114.90", "y": "29.30", "yaw": "269", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "114.32", "y": "143.89", "yaw": "269.97821", "z": "1.10" }, { "pitch": "0.0", "x": "117.59", "y": "143.89", "yaw": "269.97821", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "149.31", "y": "106.38", "yaw": "179.97821", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "72.46", "y": "109.41", "yaw": "359.97818", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "99.30", "y": "76.39", "yaw": "89", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "114.37", "y": "143.79", "yaw": "269.97821", "z": "1.10" }, { "pitch": "0.0", "x": "117.82", "y": "143.79", "yaw": "269.97821", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "149.41", "y": "106.28", "yaw": "179.97821", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "72.81", "y": "109.31", "yaw": "359.97818", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "102.80", "y": "76.30", "yaw": "89", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "147.18", "y": "217.8", "yaw": "179.97821", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "73.96", "y": "220.90", "yaw": "359.97818", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "98.40", "y": "186.69", "yaw": "89", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "147.44", "y": "216.84", "yaw": "179.97821", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "73.92", "y": "220.70", "yaw": "359.97818", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "101.90", "y": "186.60", "yaw": "89", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "60.28", "y": "185.94", "yaw": "91.264709", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "28.23", "y": "220.79", "yaw": "0.543274", "z": "1.0" } ], "right": [ { "pitch": "0.0", "x": "85.45", "y": "216.90", "yaw": "179.913574", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "65.20", "y": "245.30", "yaw": "262", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "147.53", "y": "217.14", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "101.79", "y": "186.23", "yaw": "90.0", "z": "1.0" }, { "pitch": "0.0", "x": "98.89", "y": "186.10", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "70.70", "y": "220.60", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "102.57", "y": "76.30", "yaw": "89.978363", "z": "1.10" }, { "pitch": "0.0", "x": "99.27", "y": "76.30", "yaw": "89.978363", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "72.58", "y": "109.31", "yaw": "359.978363", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "149.55", "y": "106.28", "yaw": "179.978394", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "117.60", "y": "141.30", "yaw": "269", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "102.76", "y": "76.40", "yaw": "89.978363", "z": "1.10" }, { "pitch": "0.0", "x": "99.7", "y": "76.40", "yaw": "89.978363", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "72.58", "y": "109.41", "yaw": "359.978363", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "149.8", "y": "106.38", "yaw": "179.978394", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "114.10", "y": "141.40", "yaw": "269", "z": "1.10" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-2.50", "y": "7.87", "yaw": "269.022919", "z": "1.10" }, { "pitch": "0.0", "x": "0.74", "y": "7.96", "yaw": "269.022919", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-44.24", "y": "-28.21", "yaw": "359", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-49.68", "y": "-28.63", "yaw": "0.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "0.50", "y": "2.50", "yaw": "270", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-49.21", "y": "-31.77", "yaw": "0.078583", "z": "1.10" }, { "pitch": "0.0", "x": "-49.81", "y": "-28.75", "yaw": "0.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-3.0", "y": "2.50", "yaw": "270", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "33.34", "y": "292.46", "yaw": "180.519638", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-13.30", "y": "257.80", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-86.54", "y": "211.82", "yaw": "254.81955", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-63.63", "y": "152.39", "yaw": "135.294983", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-95.40", "y": "140.40", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-94.75", "y": "65.72", "yaw": "90.502838", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-126.34", "y": "98.72", "yaw": "11.670349", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-57.9", "y": "130.96", "yaw": "213.509109", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-91.80", "y": "151.50", "yaw": "270", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-86.66", "y": "212.63", "yaw": "258.545807", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-95.85", "y": "137.68", "yaw": "90.198975", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-64.30", "y": "153.10", "yaw": "135", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "-79.74", "y": "120.70", "yaw": "33.660187", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-71.70", "y": "165.90", "yaw": "315", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-126.19", "y": "98.14", "yaw": "15.194061", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-91.47", "y": "151.90", "yaw": "270.146454", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-94.87", "y": "66.17", "yaw": "90.701965", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-64.73", "y": "126.61", "yaw": "213", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.12", "y": "156.43", "yaw": "270.462616", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-56.96", "y": "131.78", "yaw": "213.560501", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-126.46", "y": "98.24", "yaw": "14.643555", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-94.90", "y": "73.8", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "159.71", "y": "143.71", "yaw": "269.980591", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "128.25", "y": "109.94", "yaw": "359.98056", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "155.90", "y": "78.10", "yaw": "89", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "159.92", "y": "193.60", "yaw": "269.980591", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "129.2", "y": "161.46", "yaw": "359.98056", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "156.40", "y": "129.29", "yaw": "89", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "159.87", "y": "246.30", "yaw": "269.980591", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "129.25", "y": "220.60", "yaw": "359.98056", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "156.70", "y": "186.10", "yaw": "89", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "157.10", "y": "184.32", "yaw": "89.980438", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "160.3", "y": "246.61", "yaw": "269.980438", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "130.29", "y": "220.60", "yaw": "359", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "73.75", "y": "220.73", "yaw": "359.98056", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "101.8", "y": "185.70", "yaw": "89.98053", "z": "1.10" }, { "pitch": "0.0", "x": "98.39", "y": "185.67", "yaw": "89.98053", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "148.39", "y": "216.99", "yaw": "179", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "156.54", "y": "125.76", "yaw": "89.980438", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "159.99", "y": "193.77", "yaw": "269.980438", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "129.70", "y": "161.30", "yaw": "359", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.20", "y": "157.90", "yaw": "180.000015", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "60.70", "y": "127.93", "yaw": "90.0", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "64.70", "y": "192.20", "yaw": "270.0", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "33.20", "y": "161.40", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "64.39", "y": "192.47", "yaw": "270.000153", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "88.28", "y": "157.97", "yaw": "180.000122", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "30.9", "y": "161.99", "yaw": "0.000122", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "60.90", "y": "130.50", "yaw": "90", "z": "1.10" } }, { "other_actors": { "left": [ { "pitch": "0.0", "x": "156.27", "y": "73.88", "yaw": "89.980438", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "159.99", "y": "144.23", "yaw": "269.980438", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "129.70", "y": "110.10", "yaw": "359", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.26", "y": "73.77", "yaw": "89.980347", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "128.14", "y": "109.78", "yaw": "359.980347", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "160.0", "y": "141.30", "yaw": "269", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "156.47", "y": "125.29", "yaw": "89.980347", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "128.80", "y": "161.6", "yaw": "359.980347", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "160.0", "y": "192.90", "yaw": "269", "z": "1.10" } }, { "other_actors": { "right": [ { "pitch": "0.0", "x": "-13.41", "y": "252.49", "yaw": "90.519684", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "29.10", "y": "292.30", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "29.86", "y": "161.47", "yaw": "0.000214", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "64.32", "y": "191.93", "yaw": "270.000214", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "60.63", "y": "127.90", "yaw": "90.000183", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "89.40", "y": "157.80", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "60.90", "y": "128.26", "yaw": "90.000397", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "29.57", "y": "161.55", "yaw": "0.000397", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "88.40", "y": "157.80", "yaw": "180.000381", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "64.40", "y": "189.60", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.89", "y": "109.61", "yaw": "359.980377", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "114.18", "y": "144.10", "yaw": "269.980347", "z": "1.10" }, { "pitch": "0.0", "x": "117.64", "y": "144.12", "yaw": "269.980347", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "102.79", "y": "76.55", "yaw": "89.980347", "z": "1.10" }, { "pitch": "0.0", "x": "99.40", "y": "76.52", "yaw": "89.980347", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "144.89", "y": "106.59", "yaw": "179", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "157.4", "y": "180.95", "yaw": "90.950134", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "129.8", "y": "220.32", "yaw": "0.950134", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "159.71", "y": "246.60", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "141.86", "y": "-2.76", "yaw": "183.120758", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "118.74", "y": "27.65", "yaw": "269.792389", "z": "1.10" }, { "pitch": "0.0", "x": "115.49", "y": "27.78", "yaw": "269.817352", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "70.69", "y": "1.48", "yaw": "354", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "72.26", "y": "0.92", "yaw": "357.201202", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "114.79", "y": "28.3", "yaw": "269.987762", "z": "1.10" }, { "pitch": "0.0", "x": "118.50", "y": "28.7", "yaw": "269.105103", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "143.92", "y": "-2.60", "yaw": "187", "z": "1.10" } } ], "scenario_type": "Scenario4" }, { "available_event_configurations": [ { "other_actors": { "front": [ { "pitch": "359.996063", "x": "88.17", "y": "105.94", "yaw": "181.318146", "z": "0.98" } ], "left": [ { "pitch": "0.222626", "x": "60.98", "y": "72.54", "yaw": "91.318146", "z": "0.85" } ], "right": [ { "pitch": "359.777374", "x": "64.37", "y": "138.24", "yaw": "271.318146", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "33.90", "y": "105.70", "yaw": "1", "z": "0.98" } }, { "other_actors": { "front": [ { "pitch": "0.222656", "x": "60.73", "y": "72.75", "yaw": "90.305206", "z": "0.85" } ], "left": [ { "pitch": "0.0", "x": "29.18", "y": "106.1", "yaw": "0.305206", "z": "0.98" } ], "right": [ { "pitch": "0.0", "x": "87.90", "y": "105.64", "yaw": "180.305206", "z": "0.98" } ] }, "transform": { "pitch": "359", "x": "64.50", "y": "135.80", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.003937", "x": "29.19", "y": "105.80", "yaw": "1.317993", "z": "0.98" } ], "left": [ { "pitch": "359.777374", "x": "64.63", "y": "139.3", "yaw": "271.318024", "z": "1.11" } ], "right": [ { "pitch": "0.222626", "x": "60.86", "y": "72.41", "yaw": "91.317993", "z": "0.85" } ] }, "transform": { "pitch": "359", "x": "89.20", "y": "106.18", "yaw": "181", "z": "0.98" } }, { "other_actors": { "front": [ { "pitch": "359.777374", "x": "64.30", "y": "138.55", "yaw": "271.317871", "z": "1.11" } ], "left": [ { "pitch": "359.996063", "x": "88.38", "y": "106.13", "yaw": "181.317856", "z": "0.98" } ], "right": [ { "pitch": "0.003937", "x": "30.41", "y": "106.0", "yaw": "1.317841", "z": "0.98" } ] }, "transform": { "pitch": "0", "x": "61.10", "y": "76.70", "yaw": "91", "z": "0.87" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "61.44", "y": "7.36", "yaw": "89.977997", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "32.15", "y": "44.74", "yaw": "359.977997", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "64.60", "y": "74.70", "yaw": "269", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-45.91", "y": "43.99", "yaw": "0.078491", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-3.95", "y": "76.5", "yaw": "270.078491", "z": "1.10" }, { "pitch": "0.0", "x": "0.61", "y": "76.5", "yaw": "270.078491", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-9.0", "y": "9.4", "yaw": "90.078461", "z": "1.10" }, { "pitch": "0.0", "x": "-13.89", "y": "9.3", "yaw": "90.078461", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "31.10", "y": "41.10", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "31.10", "y": "41.40", "yaw": "180.078644", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-10.17", "y": "9.34", "yaw": "90.078613", "z": "1.10" }, { "pitch": "0.0", "x": "-13.86", "y": "9.34", "yaw": "90.078613", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-3.95", "y": "76.35", "yaw": "270.078613", "z": "1.10" }, { "pitch": "0.0", "x": "0.45", "y": "76.36", "yaw": "270.078613", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-45.90", "y": "44.30", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-10.15", "y": "7.97", "yaw": "90.078583", "z": "1.10" }, { "pitch": "0.0", "x": "-14.7", "y": "8.20", "yaw": "90.078583", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-45.40", "y": "43.74", "yaw": "0.078583", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "31.78", "y": "40.84", "yaw": "180.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-3.90", "y": "76.30", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-4.20", "y": "76.26", "yaw": "270.618195", "z": "1.10" }, { "pitch": "0.0", "x": "0.50", "y": "76.30", "yaw": "270.618195", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "31.36", "y": "40.65", "yaw": "180.618195", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-44.30", "y": "43.83", "yaw": "0.618164", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-10.34", "y": "12.69", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-11.52", "y": "119.39", "yaw": "90.078583", "z": "1.10" }, { "pitch": "0.0", "x": "-14.77", "y": "119.38", "yaw": "91.766205", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-41.75", "y": "145.36", "yaw": "34.068298", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "35.91", "y": "158.20", "yaw": "180.078583", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-5.50", "y": "192.40", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-6.5", "y": "252.40", "yaw": "270.078827", "z": "1.10" }, { "pitch": "0.0", "x": "-3.16", "y": "252.41", "yaw": "270.078827", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "28.77", "y": "216.93", "yaw": "180.078812", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-49.9", "y": "220.85", "yaw": "0.078796", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-12.80", "y": "187.40", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-12.85", "y": "187.4", "yaw": "90.502686", "z": "1.10" }, { "pitch": "0.0", "x": "-16.41", "y": "187.0", "yaw": "90.502686", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-49.72", "y": "220.71", "yaw": "0.502686", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "28.82", "y": "216.87", "yaw": "180.502686", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-6.30", "y": "252.10", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "29.53", "y": "217.10", "yaw": "180.502945", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-12.92", "y": "187.72", "yaw": "90.502899", "z": "1.10" }, { "pitch": "0.0", "x": "-16.2", "y": "187.70", "yaw": "90.502899", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-6.33", "y": "249.93", "yaw": "270.50293", "z": "1.10" }, { "pitch": "0.0", "x": "-3.18", "y": "250.10", "yaw": "270.50293", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-50.50", "y": "220.40", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-49.4", "y": "220.49", "yaw": "0.502808", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-6.59", "y": "249.87", "yaw": "270.502838", "z": "1.10" }, { "pitch": "0.0", "x": "-3.49", "y": "249.89", "yaw": "270.502838", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-12.50", "y": "187.76", "yaw": "90.502777", "z": "1.10" }, { "pitch": "0.0", "x": "-16.18", "y": "187.73", "yaw": "90.502777", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "31.0", "y": "217.20", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-5.74", "y": "193.45", "yaw": "270.529999", "z": "1.10" }, { "pitch": "0.0", "x": "-2.19", "y": "193.49", "yaw": "270.529999", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "36.69", "y": "158.0", "yaw": "180.529984", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-41.67", "y": "145.65", "yaw": "35.881683", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-11.70", "y": "120.39", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "37.5", "y": "158.71", "yaw": "181.3517", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-12.29", "y": "122.23", "yaw": "88.502625", "z": "1.10" }, { "pitch": "0.0", "x": "-14.96", "y": "121.11", "yaw": "90.477356", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-5.41", "y": "191.12", "yaw": "271.922607", "z": "1.10" }, { "pitch": "0.0", "x": "-2.14", "y": "192.27", "yaw": "271.895691", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-41.80", "y": "145.71", "yaw": "32", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-41.66", "y": "145.74", "yaw": "34.578308", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-5.57", "y": "192.64", "yaw": "270.078796", "z": "1.10" }, { "pitch": "0.0", "x": "-2.14", "y": "192.64", "yaw": "270.078796", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-11.82", "y": "120.8", "yaw": "90.078735", "z": "1.10" }, { "pitch": "0.0", "x": "-14.95", "y": "120.0", "yaw": "90.078735", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "31.40", "y": "158.10", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "148.99", "y": "106.64", "yaw": "181.318146", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "103.3", "y": "76.35", "yaw": "91.318115", "z": "1.10" }, { "pitch": "0.0", "x": "99.31", "y": "76.28", "yaw": "91.318115", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "114.31", "y": "143.85", "yaw": "271.318115", "z": "1.10" }, { "pitch": "0.0", "x": "117.86", "y": "143.94", "yaw": "271.318115", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "73.90", "y": "109.30", "yaw": "1", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "114.37", "y": "143.79", "yaw": "269.97821", "z": "1.10" }, { "pitch": "0.0", "x": "117.82", "y": "143.79", "yaw": "269.97821", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "149.41", "y": "106.28", "yaw": "179.97821", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "72.81", "y": "109.31", "yaw": "359.97818", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "102.80", "y": "76.30", "yaw": "89", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "147.53", "y": "217.14", "yaw": "180.000015", "z": "1.0" } ], "left": [ { "pitch": "0.0", "x": "101.79", "y": "186.23", "yaw": "90.0", "z": "1.0" }, { "pitch": "0.0", "x": "98.89", "y": "186.10", "yaw": "90.0", "z": "1.0" } ] }, "transform": { "pitch": "0", "x": "70.70", "y": "220.60", "yaw": "0", "z": "1.0" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "102.76", "y": "76.40", "yaw": "89.978363", "z": "1.10" }, { "pitch": "0.0", "x": "99.7", "y": "76.40", "yaw": "89.978363", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "72.58", "y": "109.41", "yaw": "359.978363", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "149.8", "y": "106.38", "yaw": "179.978394", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "114.10", "y": "141.40", "yaw": "269", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-86.54", "y": "211.82", "yaw": "254.81955", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-63.63", "y": "152.39", "yaw": "135.294983", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-95.40", "y": "140.40", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-94.75", "y": "65.72", "yaw": "90.502838", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-126.34", "y": "98.72", "yaw": "11.670349", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-57.9", "y": "130.96", "yaw": "213.509109", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-91.80", "y": "151.50", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-126.19", "y": "98.14", "yaw": "15.194061", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-91.47", "y": "151.90", "yaw": "270.146454", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-94.87", "y": "66.17", "yaw": "90.701965", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-64.73", "y": "126.61", "yaw": "213", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "-92.12", "y": "156.43", "yaw": "270.462616", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "-56.96", "y": "131.78", "yaw": "213.560501", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "-126.46", "y": "98.24", "yaw": "14.643555", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "-94.90", "y": "73.8", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "88.20", "y": "157.90", "yaw": "180.000015", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "60.70", "y": "127.93", "yaw": "90.0", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "64.70", "y": "192.20", "yaw": "270.0", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "33.20", "y": "161.40", "yaw": "0", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "64.39", "y": "192.47", "yaw": "270.000153", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "88.28", "y": "157.97", "yaw": "180.000122", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "30.9", "y": "161.99", "yaw": "0.000122", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "60.90", "y": "130.50", "yaw": "90", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "29.86", "y": "161.47", "yaw": "0.000214", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "64.32", "y": "191.93", "yaw": "270.000214", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "60.63", "y": "127.90", "yaw": "90.000183", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "89.40", "y": "157.80", "yaw": "180", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "60.90", "y": "128.26", "yaw": "90.000397", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "29.57", "y": "161.55", "yaw": "0.000397", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "88.40", "y": "157.80", "yaw": "180.000381", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "64.40", "y": "189.60", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "74.89", "y": "109.61", "yaw": "359.980377", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "114.18", "y": "144.10", "yaw": "269.980347", "z": "1.10" }, { "pitch": "0.0", "x": "117.64", "y": "144.12", "yaw": "269.980347", "z": "1.10" } ], "right": [ { "pitch": "0.0", "x": "102.79", "y": "76.55", "yaw": "89.980347", "z": "1.10" }, { "pitch": "0.0", "x": "99.40", "y": "76.52", "yaw": "89.980347", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "144.89", "y": "106.59", "yaw": "179", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "157.4", "y": "180.95", "yaw": "90.950134", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "129.8", "y": "220.32", "yaw": "0.950134", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "159.71", "y": "246.60", "yaw": "270", "z": "1.10" } }, { "other_actors": { "front": [ { "pitch": "0.0", "x": "72.26", "y": "0.92", "yaw": "357.201202", "z": "1.10" } ], "left": [ { "pitch": "0.0", "x": "114.79", "y": "28.3", "yaw": "269.987762", "z": "1.10" }, { "pitch": "0.0", "x": "118.50", "y": "28.7", "yaw": "269.105103", "z": "1.10" } ] }, "transform": { "pitch": "0", "x": "143.92", "y": "-2.60", "yaw": "187", "z": "1.10" } } ], "scenario_type": "Scenario8" } ] } ] } ================================================ FILE: scenario_runner/srunner/data/no_scenarios.json ================================================ { "available_scenarios": [ { } ] } ================================================ FILE: scenario_runner/srunner/data/routes_debug.xml ================================================ ================================================ FILE: scenario_runner/srunner/data/routes_devtest.xml ================================================ ================================================ FILE: scenario_runner/srunner/data/routes_training.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/CatalogExample.xosc ================================================ ================================================ FILE: scenario_runner/srunner/examples/ChangeLane.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/ChangingWeather.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/ControlLoss.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/CutIn.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/CyclistCrossing.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/FollowLeadingVehicle.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/FollowLeadingVehicle.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/FreeRide.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/LaneChangeSimple.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/LeadingVehicle.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/NoSignalJunction.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/ObjectCrossing.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/OppositeDirection.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/OscControllerExample.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/PedestrianCrossingFront.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/RunningRedLight.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/SignalizedJunctionLeftTurn.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/SignalizedJunctionRightTurn.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/VehicleTurning.xml ================================================ ================================================ FILE: scenario_runner/srunner/examples/catalogs/ControllerCatalog.xosc ================================================ ================================================ FILE: scenario_runner/srunner/examples/catalogs/EnvironmentCatalog.xosc ================================================ ================================================ FILE: scenario_runner/srunner/examples/catalogs/ManeuverCatalog.xosc ================================================ ================================================ FILE: scenario_runner/srunner/examples/catalogs/MiscObjectCatalog.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/catalogs/PedestrianCatalog.xosc ================================================
================================================ FILE: scenario_runner/srunner/examples/catalogs/VehicleCatalog.xosc ================================================
================================================ FILE: scenario_runner/srunner/metrics/data/CriteriaFilter_criteria.json ================================================ { "RouteCompletionTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "SUCCESS", "expected_value_success": 100, "expected_value_acceptable": null, "actual_value": 100, "optional": false, "_wsize": 2, "_current_index": 759, "_route_length": 762, "_accum_meters": [ 0.0, 1.1180341243743896, 2.118034243583679, 3.1180343627929688, 4.118034482002258, 5.118034601211548, 6.118034720420837, 7.118034839630127, 8.118034958839417, 9.118035078048706, 10.118035197257996, 11.118035316467285, 12.118035435676575, 13.118035554885864, 14.118035674095154, 15.118035793304443, 16.118035912513733, 17.408029437065125, 17.408029437065125, 18.408029556274414, 19.408029675483704, 20.408029794692993, 21.408029913902283, 22.60914123058319, 23.882590174674988, 25.156023859977722, 26.42948305606842, 27.702926516532898, 28.976354002952576, 30.22618818283081, 31.444236278533936, 32.66231644153595, 33.88036382198334, 35.098384618759155, 36.31645858287811, 37.5344922542572, 38.54053473472595, 40.18173956871033, 40.18173956871033, 41.18173956871033, 42.18173956871033, 44.18173956871033, 45.18173956871033, 46.18173956871033, 47.18173956871033, 48.18173956871033, 49.18173956871033, 50.18173956871033, 51.18173956871033, 52.18173956871033, 53.18173956871033, 54.18173956871033, 55.18173956871033, 56.18173956871033, 57.18173956871033, 58.18173956871033, 59.18173956871033, 60.18173956871033, 61.18173956871033, 62.18173956871033, 63.18173956871033, 64.18173956871033, 65.18173956871033, 66.18173956871033, 67.18173956871033, 68.18173956871033, 69.18173956871033, 70.18173956871033, 71.18173956871033, 72.18173956871033, 73.18173956871033, 74.18173956871033, 75.18173956871033, 76.18173956871033, 77.18173956871033, 78.18173956871033, 79.18173956871033, 80.18173956871033, 81.18173956871033, 82.18173956871033, 83.18173956871033, 84.18173956871033, 85.18173956871033, 86.18173956871033, 87.18173956871033, 88.18173956871033, 89.18173956871033, 90.18173956871033, 91.18173956871033, 92.18173956871033, 93.18173956871033, 94.18173956871033, 95.18173956871033, 96.18173956871033, 97.18173956871033, 98.18173956871033, 99.18173956871033, 100.18173956871033, 101.18173956871033, 102.18173956871033, 103.18173956871033, 104.18173956871033, 105.18173956871033, 106.18173956871033, 107.18173956871033, 108.18173956871033, 109.18173956871033, 110.1817090511322, 111.1817090511322, 112.1817090511322, 113.1817090511322, 114.1817090511322, 115.1817090511322, 116.1817090511322, 117.1817090511322, 118.1817090511322, 119.1817090511322, 120.1817090511322, 121.1817090511322, 122.1817090511322, 123.1817090511322, 124.1817090511322, 125.1817090511322, 126.1817090511322, 127.1817090511322, 128.1817090511322, 129.1817090511322, 130.1817090511322, 131.1817090511322, 132.1817090511322, 133.1817090511322, 134.1817090511322, 135.1817090511322, 136.1817090511322, 137.1817090511322, 138.1817090511322, 139.1817090511322, 140.1817090511322, 141.1817090511322, 142.1817090511322, 143.1817090511322, 144.1817090511322, 145.1817090511322, 146.1817090511322, 147.1817090511322, 148.1817090511322, 149.1817090511322, 150.1817090511322, 151.1817090511322, 152.1817090511322, 153.1817090511322, 154.1817090511322, 155.1817090511322, 156.1817090511322, 157.1817090511322, 158.1817090511322, 159.1817090511322, 160.1817090511322, 161.1817090511322, 162.1817090511322, 163.1817090511322, 164.1817090511322, 165.1817090511322, 166.1817090511322, 167.1817090511322, 168.1817090511322, 169.1817090511322, 170.1817090511322, 171.1817090511322, 172.1817090511322, 173.1817090511322, 174.1817090511322, 175.1817090511322, 176.1817090511322, 177.1817090511322, 178.1817090511322, 179.1817090511322, 180.1817090511322, 181.1817090511322, 182.1817090511322, 183.1817090511322, 184.1817090511322, 185.1817090511322, 186.1817090511322, 187.1817090511322, 188.1817090511322, 189.1817090511322, 190.1817090511322, 191.1817090511322, 192.1817090511322, 193.1817090511322, 194.1817090511322, 195.1817090511322, 196.1817090511322, 197.1817090511322, 198.1817090511322, 199.1817090511322, 200.1817090511322, 201.1817090511322, 202.1817090511322, 203.1817090511322, 204.1817090511322, 205.1817090511322, 206.1817090511322, 207.1817090511322, 208.1817090511322, 209.1817090511322, 210.1817090511322, 211.1817090511322, 212.1817090511322, 213.1817090511322, 214.1817090511322, 215.1817090511322, 216.1817090511322, 217.1817090511322, 218.1817090511322, 219.1817090511322, 220.1817090511322, 221.1817090511322, 222.1817090511322, 223.1817090511322, 224.1817090511322, 225.1817090511322, 226.1817090511322, 227.1817090511322, 228.1817090511322, 229.1817090511322, 230.1817090511322, 231.1817090511322, 232.1817090511322, 233.1817090511322, 234.1817090511322, 235.1817090511322, 236.1817090511322, 237.1817090511322, 238.18171668052673, 239.18171668052673, 240.18171668052673, 241.18171668052673, 242.18171668052673, 243.18171668052673, 244.18171668052673, 245.18171668052673, 246.18171668052673, 247.18171668052673, 248.18171668052673, 249.18171668052673, 250.18171668052673, 251.18171668052673, 252.18171668052673, 253.18171668052673, 254.18171668052673, 255.18171668052673, 256.18171668052673, 258.18171668052673, 259.18171668052673, 260.18171668052673, 261.18171668052673, 262.18171668052673, 263.18171668052673, 264.43171668052673, 264.43171668052673, 265.43171668052673, 266.4848858118057, 267.6947091817856, 268.9045317173004, 270.11435973644257, 271.3241786956787, 272.53399670124054, 273.74381709098816, 274.95476615428925, 276.1825375556946, 277.41030740737915, 278.6380902528763, 279.86586582660675, 281.093638420105, 282.32140839099884, 283.54918599128723, 284.56516194343567, 285.86318135261536, 285.86318135261536, 286.86318135261536, 287.86318135261536, 288.86318135261536, 289.86318135261536, 290.86318135261536, 291.86318135261536, 292.86318135261536, 293.86318135261536, 294.86318135261536, 295.86318135261536, 296.86318135261536, 297.86318135261536, 298.86318135261536, 299.86318135261536, 300.86318135261536, 301.86318135261536, 302.86318135261536, 303.86318135261536, 304.86318135261536, 305.86318135261536, 306.86318135261536, 307.86318135261536, 308.86318135261536, 309.86318135261536, 310.86318135261536, 311.86318135261536, 312.86318135261536, 313.86318135261536, 314.86318135261536, 315.86318135261536, 316.86318135261536, 317.86318135261536, 318.86318135261536, 319.86318135261536, 320.86318135261536, 321.86318135261536, 322.86318135261536, 323.86318135261536, 324.86318135261536, 325.86318135261536, 326.86318135261536, 327.86318135261536, 328.86318135261536, 329.86318135261536, 330.86318135261536, 331.86318135261536, 332.86318135261536, 333.8631966114044, 334.8631966114044, 335.8631966114044, 336.8631966114044, 337.8631966114044, 338.8631966114044, 339.8631966114044, 340.8631966114044, 341.8631966114044, 342.8631966114044, 343.8631966114044, 344.8631966114044, 345.8631966114044, 346.8631966114044, 347.8631966114044, 348.8631966114044, 349.8631966114044, 350.8631966114044, 351.8631966114044, 352.8631966114044, 353.8631966114044, 354.8631966114044, 355.8631966114044, 356.8631966114044, 357.8631966114044, 358.8631966114044, 359.8631966114044, 360.8631966114044, 361.8631966114044, 362.8631966114044, 363.8631966114044, 364.8631966114044, 365.8631966114044, 366.8631966114044, 367.8631966114044, 368.8631966114044, 369.8631966114044, 370.8631966114044, 371.8631966114044, 372.8631966114044, 373.8631966114044, 374.8631966114044, 375.8631966114044, 376.8631966114044, 377.8631966114044, 378.8631966114044, 379.8631966114044, 380.8631966114044, 381.8631966114044, 382.8631966114044, 383.8631966114044, 384.8631966114044, 385.8631966114044, 386.8631966114044, 387.8631966114044, 388.8631966114044, 389.8631966114044, 390.8631966114044, 391.8631966114044, 392.8631966114044, 394.8331673145294, 394.8331673145294, 395.6912509202957, 396.5167629122734, 397.34227895736694, 398.1678013205528, 398.9933475255966, 399.81885331869125, 400.6444185972214, 401.4699310064316, 402.290342271328, 403.09512996673584, 403.8999582529068, 404.70476245880127, 405.509556889534, 406.314362347126, 407.1191706061363, 407.92396891117096, 409.09423565864563, 409.09423565864563, 410.0942357778549, 411.0942358970642, 412.0942360162735, 413.0942361354828, 414.0942362546921, 415.09423637390137, 416.09423649311066, 417.09423661231995, 418.09423673152924, 419.0942368507385, 420.0942369699478, 421.0942370891571, 422.0942372083664, 423.0942373275757, 424.094237446785, 425.094233751297, 426.0942338705063, 427.0942339897156, 428.09423410892487, 429.09423422813416, 430.09423434734344, 431.09423446655273, 432.094234585762, 433.0942347049713, 434.0942348241806, 435.0942349433899, 436.0942350625992, 437.0942351818085, 438.09423530101776, 439.09423542022705, 440.09423553943634, 441.09423565864563, 442.0942357778549, 443.0942358970642, 444.0942360162735, 445.0942361354828, 446.0942362546921, 447.0942325592041, 448.0942326784134, 449.0942327976227, 450.09423291683197, 451.09423303604126, 452.09423315525055, 453.0942294597626, 454.09422957897186, 455.09422969818115, 456.09422981739044, 457.09423184394836, 458.09423196315765, 459.09423208236694, 460.09423220157623, 461.0942323207855, 462.0942324399948, 463.09423065185547, 464.09423077106476, 465.09423089027405, 466.09423100948334, 467.0942311286926, 468.0942312479019, 469.0942313671112, 470.0942314863205, 471.0942316055298, 472.0942317247391, 473.0942327976227, 474.09423291683197, 475.09423303604126, 476.09423315525055, 477.0942323207855, 478.724232673645, 478.724232673645, 479.64406257867813, 480.41382187604904, 481.18358182907104, 481.9533463716507, 482.7230935692787, 483.4928572177887, 484.2626251578331, 485.03238236904144, 485.8388220667839, 486.66605401039124, 487.49329620599747, 488.3205181956291, 489.1477633714676, 489.9749982357025, 490.802244246006, 492.28208762407303, 492.28208762407303, 493.28208762407303, 494.28208762407303, 495.28208762407303, 496.28208762407303, 497.28208762407303, 498.28208762407303, 499.28208762407303, 500.28208762407303, 501.28208762407303, 502.28208762407303, 503.28208762407303, 504.28208762407303, 505.28208762407303, 506.28208762407303, 507.28208762407303, 508.28208762407303, 509.28208762407303, 510.28208762407303, 511.28208762407303, 512.282087624073, 513.282087624073, 514.282087624073, 515.282087624073, 516.282087624073, 517.282087624073, 518.282087624073, 519.282087624073, 520.282087624073, 521.282087624073, 522.282087624073, 523.282087624073, 524.282087624073, 525.282087624073, 526.282087624073, 527.282087624073, 528.282087624073, 529.282087624073, 530.282087624073, 531.282087624073, 532.282087624073, 533.282087624073, 534.282087624073, 535.282087624073, 536.282087624073, 537.282087624073, 538.282087624073, 539.282087624073, 540.282087624073, 541.282087624073, 542.282087624073, 543.282087624073, 544.282087624073, 545.282087624073, 546.282087624073, 547.282087624073, 548.282087624073, 549.282087624073, 550.282087624073, 551.282087624073, 552.282087624073, 553.282087624073, 554.2821028828621, 555.2821028828621, 556.2821028828621, 557.2821028828621, 558.2821028828621, 559.2821028828621, 560.2821028828621, 561.2821028828621, 562.2821028828621, 563.2821028828621, 564.2821028828621, 565.2821028828621, 566.2821028828621, 567.2821028828621, 568.2821028828621, 569.2833998799324, 570.2833999991417, 571.283400118351, 572.2834002375603, 573.2834003567696, 574.2834004759789, 575.2834005951881, 576.2834007143974, 577.2834008336067, 578.283400952816, 579.2834010720253, 580.2834011912346, 581.2834013104439, 582.2834014296532, 583.2834015488625, 584.2834016680717, 585.283401787281, 586.2834019064903, 587.2834020256996, 588.2834021449089, 589.2834022641182, 590.2834023833275, 591.2834025025368, 592.2834026217461, 593.2834027409554, 594.2834028601646, 595.2834029793739, 596.2834030985832, 597.2834032177925, 598.2834033370018, 599.2834034562111, 600.2834035754204, 601.2834036946297, 602.283403813839, 603.2834039330482, 604.2834040522575, 605.2834041714668, 606.2834042906761, 607.2834044098854, 608.2834045290947, 609.283404648304, 610.2834047675133, 611.2834048867226, 612.2834050059319, 613.2834051251411, 614.2834052443504, 615.2834053635597, 616.283405482769, 617.2834056019783, 618.2834057211876, 619.2834058403969, 620.2834059596062, 621.2834060788155, 622.2834061980247, 623.283406317234, 624.2834064364433, 625.2834065556526, 626.2834066748619, 627.2834067940712, 628.2834069132805, 629.2834070324898, 630.2834071516991, 631.2834072709084, 632.2834073901176, 633.2834075093269, 634.2834076285362, 635.2834077477455, 636.2834078669548, 637.2834079861641, 639.2834082245827, 640.283408343792, 641.2834084630013, 642.2834085822105, 643.2834087014198, 644.2834088206291, 645.2834089398384, 646.2834090590477, 647.283409178257, 648.2834092974663, 649.2834094166756, 650.2834095358849, 651.2834096550941, 652.2833945155144, 653.2833946347237, 654.283394753933, 655.2833948731422, 656.2833949923515, 657.2833951115608, 658.2833952307701, 659.2833953499794, 660.2833954691887, 661.283395588398, 662.2833957076073, 663.2833958268166, 664.2833959460258, 665.2833960652351, 666.2833961844444, 667.2833963036537, 668.283396422863, 669.2833965420723, 670.2833966612816, 671.2833967804909, 672.2833968997002, 673.2833970189095, 674.2833971381187, 675.283397257328, 676.2833973765373, 677.2833974957466, 678.2833976149559, 679.2833977341652, 680.2833978533745, 681.2833979725838, 682.2834057211876, 683.2834058403969, 684.2834059596062, 685.2834060788155, 686.2834061980247, 687.283406317234, 688.2834064364433, 689.2834065556526, 690.2834066748619, 691.2834067940712, 692.2834069132805, 693.2834070324898, 694.2834071516991, 695.2834072709084, 696.2834073901176, 697.2834075093269, 698.2834076285362, 699.2834077477455, 700.2834078669548, 701.2834079861641, 702.2834081053734, 703.2834082245827, 704.283408343792, 705.2834084630013, 706.2834085822105, 707.2834087014198, 708.2834088206291, 709.2834089398384, 710.2834090590477, 711.283409178257, 712.2834016680717, 713.283401787281, 714.2834019064903, 715.2834020256996, 716.2834021449089, 717.2834022641182, 718.2834023833275, 719.2834025025368, 720.2834026217461, 721.2834027409554, 722.2815870046616, 723.2815870046616, 724.2815870046616, 725.2815870046616, 726.2815870046616, 727.2815870046616, 728.2815870046616, 729.2815870046616, 730.2815870046616, 731.2815870046616, 732.2815870046616, 733.2815870046616, 734.2815870046616, 735.2815870046616, 736.2815870046616, 737.2815870046616, 738.2815870046616, 739.2815870046616, 740.2815870046616, 741.2815870046616, 742.2815870046616, 743.2815870046616, 744.2815870046616, 745.2815870046616, 746.2815870046616, 747.2815870046616, 748.2815870046616, 749.2815870046616, 750.2815870046616, 751.2815870046616, 752.2815870046616, 753.2815870046616, 754.2815870046616, 755.2815870046616, 756.2815870046616, 757.2815870046616, 758.2815870046616, 759.2815870046616, 760.2815870046616 ], "_percentage_route_completed": 100, "terminate_on_failure": false }, "CollisionTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "FAILURE", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 5, "optional": false, "_collision_sensor": null, "other_actor": null, "other_actor_type": null, "registered_collisions": [], "last_id": null, "collision_time": 70.1000010445714, "terminate_on_failure": false }, "InRouteTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": true, "test_status": "SUCCESS", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 0, "optional": false, "list_traffic_events": [], "_offroad_max": 30, "_offroad_min": 15.0, "_route_length": 762, "_current_index": 760, "_out_route_distance": 0, "_in_safe_route": true, "_accum_meters": [ 0.0, 1.1180341243743896, 2.118034243583679, 3.1180343627929688, 4.118034482002258, 5.118034601211548, 6.118034720420837, 7.118034839630127, 8.118034958839417, 9.118035078048706, 10.118035197257996, 11.118035316467285, 12.118035435676575, 13.118035554885864, 14.118035674095154, 15.118035793304443, 16.118035912513733, 17.408029437065125, 17.408029437065125, 18.408029556274414, 19.408029675483704, 20.408029794692993, 21.408029913902283, 22.60914123058319, 23.882590174674988, 25.156023859977722, 26.42948305606842, 27.702926516532898, 28.976354002952576, 30.22618818283081, 31.444236278533936, 32.66231644153595, 33.88036382198334, 35.098384618759155, 36.31645858287811, 37.5344922542572, 38.54053473472595, 40.18173956871033, 40.18173956871033, 41.18173956871033, 42.18173956871033, 44.18173956871033, 45.18173956871033, 46.18173956871033, 47.18173956871033, 48.18173956871033, 49.18173956871033, 50.18173956871033, 51.18173956871033, 52.18173956871033, 53.18173956871033, 54.18173956871033, 55.18173956871033, 56.18173956871033, 57.18173956871033, 58.18173956871033, 59.18173956871033, 60.18173956871033, 61.18173956871033, 62.18173956871033, 63.18173956871033, 64.18173956871033, 65.18173956871033, 66.18173956871033, 67.18173956871033, 68.18173956871033, 69.18173956871033, 70.18173956871033, 71.18173956871033, 72.18173956871033, 73.18173956871033, 74.18173956871033, 75.18173956871033, 76.18173956871033, 77.18173956871033, 78.18173956871033, 79.18173956871033, 80.18173956871033, 81.18173956871033, 82.18173956871033, 83.18173956871033, 84.18173956871033, 85.18173956871033, 86.18173956871033, 87.18173956871033, 88.18173956871033, 89.18173956871033, 90.18173956871033, 91.18173956871033, 92.18173956871033, 93.18173956871033, 94.18173956871033, 95.18173956871033, 96.18173956871033, 97.18173956871033, 98.18173956871033, 99.18173956871033, 100.18173956871033, 101.18173956871033, 102.18173956871033, 103.18173956871033, 104.18173956871033, 105.18173956871033, 106.18173956871033, 107.18173956871033, 108.18173956871033, 109.18173956871033, 110.1817090511322, 111.1817090511322, 112.1817090511322, 113.1817090511322, 114.1817090511322, 115.1817090511322, 116.1817090511322, 117.1817090511322, 118.1817090511322, 119.1817090511322, 120.1817090511322, 121.1817090511322, 122.1817090511322, 123.1817090511322, 124.1817090511322, 125.1817090511322, 126.1817090511322, 127.1817090511322, 128.1817090511322, 129.1817090511322, 130.1817090511322, 131.1817090511322, 132.1817090511322, 133.1817090511322, 134.1817090511322, 135.1817090511322, 136.1817090511322, 137.1817090511322, 138.1817090511322, 139.1817090511322, 140.1817090511322, 141.1817090511322, 142.1817090511322, 143.1817090511322, 144.1817090511322, 145.1817090511322, 146.1817090511322, 147.1817090511322, 148.1817090511322, 149.1817090511322, 150.1817090511322, 151.1817090511322, 152.1817090511322, 153.1817090511322, 154.1817090511322, 155.1817090511322, 156.1817090511322, 157.1817090511322, 158.1817090511322, 159.1817090511322, 160.1817090511322, 161.1817090511322, 162.1817090511322, 163.1817090511322, 164.1817090511322, 165.1817090511322, 166.1817090511322, 167.1817090511322, 168.1817090511322, 169.1817090511322, 170.1817090511322, 171.1817090511322, 172.1817090511322, 173.1817090511322, 174.1817090511322, 175.1817090511322, 176.1817090511322, 177.1817090511322, 178.1817090511322, 179.1817090511322, 180.1817090511322, 181.1817090511322, 182.1817090511322, 183.1817090511322, 184.1817090511322, 185.1817090511322, 186.1817090511322, 187.1817090511322, 188.1817090511322, 189.1817090511322, 190.1817090511322, 191.1817090511322, 192.1817090511322, 193.1817090511322, 194.1817090511322, 195.1817090511322, 196.1817090511322, 197.1817090511322, 198.1817090511322, 199.1817090511322, 200.1817090511322, 201.1817090511322, 202.1817090511322, 203.1817090511322, 204.1817090511322, 205.1817090511322, 206.1817090511322, 207.1817090511322, 208.1817090511322, 209.1817090511322, 210.1817090511322, 211.1817090511322, 212.1817090511322, 213.1817090511322, 214.1817090511322, 215.1817090511322, 216.1817090511322, 217.1817090511322, 218.1817090511322, 219.1817090511322, 220.1817090511322, 221.1817090511322, 222.1817090511322, 223.1817090511322, 224.1817090511322, 225.1817090511322, 226.1817090511322, 227.1817090511322, 228.1817090511322, 229.1817090511322, 230.1817090511322, 231.1817090511322, 232.1817090511322, 233.1817090511322, 234.1817090511322, 235.1817090511322, 236.1817090511322, 237.1817090511322, 238.18171668052673, 239.18171668052673, 240.18171668052673, 241.18171668052673, 242.18171668052673, 243.18171668052673, 244.18171668052673, 245.18171668052673, 246.18171668052673, 247.18171668052673, 248.18171668052673, 249.18171668052673, 250.18171668052673, 251.18171668052673, 252.18171668052673, 253.18171668052673, 254.18171668052673, 255.18171668052673, 256.18171668052673, 258.18171668052673, 259.18171668052673, 260.18171668052673, 261.18171668052673, 262.18171668052673, 263.18171668052673, 264.43171668052673, 264.43171668052673, 265.43171668052673, 266.4848858118057, 267.6947091817856, 268.9045317173004, 270.11435973644257, 271.3241786956787, 272.53399670124054, 273.74381709098816, 274.95476615428925, 276.1825375556946, 277.41030740737915, 278.6380902528763, 279.86586582660675, 281.093638420105, 282.32140839099884, 283.54918599128723, 284.56516194343567, 285.86318135261536, 285.86318135261536, 286.86318135261536, 287.86318135261536, 288.86318135261536, 289.86318135261536, 290.86318135261536, 291.86318135261536, 292.86318135261536, 293.86318135261536, 294.86318135261536, 295.86318135261536, 296.86318135261536, 297.86318135261536, 298.86318135261536, 299.86318135261536, 300.86318135261536, 301.86318135261536, 302.86318135261536, 303.86318135261536, 304.86318135261536, 305.86318135261536, 306.86318135261536, 307.86318135261536, 308.86318135261536, 309.86318135261536, 310.86318135261536, 311.86318135261536, 312.86318135261536, 313.86318135261536, 314.86318135261536, 315.86318135261536, 316.86318135261536, 317.86318135261536, 318.86318135261536, 319.86318135261536, 320.86318135261536, 321.86318135261536, 322.86318135261536, 323.86318135261536, 324.86318135261536, 325.86318135261536, 326.86318135261536, 327.86318135261536, 328.86318135261536, 329.86318135261536, 330.86318135261536, 331.86318135261536, 332.86318135261536, 333.8631966114044, 334.8631966114044, 335.8631966114044, 336.8631966114044, 337.8631966114044, 338.8631966114044, 339.8631966114044, 340.8631966114044, 341.8631966114044, 342.8631966114044, 343.8631966114044, 344.8631966114044, 345.8631966114044, 346.8631966114044, 347.8631966114044, 348.8631966114044, 349.8631966114044, 350.8631966114044, 351.8631966114044, 352.8631966114044, 353.8631966114044, 354.8631966114044, 355.8631966114044, 356.8631966114044, 357.8631966114044, 358.8631966114044, 359.8631966114044, 360.8631966114044, 361.8631966114044, 362.8631966114044, 363.8631966114044, 364.8631966114044, 365.8631966114044, 366.8631966114044, 367.8631966114044, 368.8631966114044, 369.8631966114044, 370.8631966114044, 371.8631966114044, 372.8631966114044, 373.8631966114044, 374.8631966114044, 375.8631966114044, 376.8631966114044, 377.8631966114044, 378.8631966114044, 379.8631966114044, 380.8631966114044, 381.8631966114044, 382.8631966114044, 383.8631966114044, 384.8631966114044, 385.8631966114044, 386.8631966114044, 387.8631966114044, 388.8631966114044, 389.8631966114044, 390.8631966114044, 391.8631966114044, 392.8631966114044, 394.8331673145294, 394.8331673145294, 395.6912509202957, 396.5167629122734, 397.34227895736694, 398.1678013205528, 398.9933475255966, 399.81885331869125, 400.6444185972214, 401.4699310064316, 402.290342271328, 403.09512996673584, 403.8999582529068, 404.70476245880127, 405.509556889534, 406.314362347126, 407.1191706061363, 407.92396891117096, 409.09423565864563, 409.09423565864563, 410.0942357778549, 411.0942358970642, 412.0942360162735, 413.0942361354828, 414.0942362546921, 415.09423637390137, 416.09423649311066, 417.09423661231995, 418.09423673152924, 419.0942368507385, 420.0942369699478, 421.0942370891571, 422.0942372083664, 423.0942373275757, 424.094237446785, 425.094233751297, 426.0942338705063, 427.0942339897156, 428.09423410892487, 429.09423422813416, 430.09423434734344, 431.09423446655273, 432.094234585762, 433.0942347049713, 434.0942348241806, 435.0942349433899, 436.0942350625992, 437.0942351818085, 438.09423530101776, 439.09423542022705, 440.09423553943634, 441.09423565864563, 442.0942357778549, 443.0942358970642, 444.0942360162735, 445.0942361354828, 446.0942362546921, 447.0942325592041, 448.0942326784134, 449.0942327976227, 450.09423291683197, 451.09423303604126, 452.09423315525055, 453.0942294597626, 454.09422957897186, 455.09422969818115, 456.09422981739044, 457.09423184394836, 458.09423196315765, 459.09423208236694, 460.09423220157623, 461.0942323207855, 462.0942324399948, 463.09423065185547, 464.09423077106476, 465.09423089027405, 466.09423100948334, 467.0942311286926, 468.0942312479019, 469.0942313671112, 470.0942314863205, 471.0942316055298, 472.0942317247391, 473.0942327976227, 474.09423291683197, 475.09423303604126, 476.09423315525055, 477.0942323207855, 478.724232673645, 478.724232673645, 479.64406257867813, 480.41382187604904, 481.18358182907104, 481.9533463716507, 482.7230935692787, 483.4928572177887, 484.2626251578331, 485.03238236904144, 485.8388220667839, 486.66605401039124, 487.49329620599747, 488.3205181956291, 489.1477633714676, 489.9749982357025, 490.802244246006, 492.28208762407303, 492.28208762407303, 493.28208762407303, 494.28208762407303, 495.28208762407303, 496.28208762407303, 497.28208762407303, 498.28208762407303, 499.28208762407303, 500.28208762407303, 501.28208762407303, 502.28208762407303, 503.28208762407303, 504.28208762407303, 505.28208762407303, 506.28208762407303, 507.28208762407303, 508.28208762407303, 509.28208762407303, 510.28208762407303, 511.28208762407303, 512.282087624073, 513.282087624073, 514.282087624073, 515.282087624073, 516.282087624073, 517.282087624073, 518.282087624073, 519.282087624073, 520.282087624073, 521.282087624073, 522.282087624073, 523.282087624073, 524.282087624073, 525.282087624073, 526.282087624073, 527.282087624073, 528.282087624073, 529.282087624073, 530.282087624073, 531.282087624073, 532.282087624073, 533.282087624073, 534.282087624073, 535.282087624073, 536.282087624073, 537.282087624073, 538.282087624073, 539.282087624073, 540.282087624073, 541.282087624073, 542.282087624073, 543.282087624073, 544.282087624073, 545.282087624073, 546.282087624073, 547.282087624073, 548.282087624073, 549.282087624073, 550.282087624073, 551.282087624073, 552.282087624073, 553.282087624073, 554.2821028828621, 555.2821028828621, 556.2821028828621, 557.2821028828621, 558.2821028828621, 559.2821028828621, 560.2821028828621, 561.2821028828621, 562.2821028828621, 563.2821028828621, 564.2821028828621, 565.2821028828621, 566.2821028828621, 567.2821028828621, 568.2821028828621, 569.2833998799324, 570.2833999991417, 571.283400118351, 572.2834002375603, 573.2834003567696, 574.2834004759789, 575.2834005951881, 576.2834007143974, 577.2834008336067, 578.283400952816, 579.2834010720253, 580.2834011912346, 581.2834013104439, 582.2834014296532, 583.2834015488625, 584.2834016680717, 585.283401787281, 586.2834019064903, 587.2834020256996, 588.2834021449089, 589.2834022641182, 590.2834023833275, 591.2834025025368, 592.2834026217461, 593.2834027409554, 594.2834028601646, 595.2834029793739, 596.2834030985832, 597.2834032177925, 598.2834033370018, 599.2834034562111, 600.2834035754204, 601.2834036946297, 602.283403813839, 603.2834039330482, 604.2834040522575, 605.2834041714668, 606.2834042906761, 607.2834044098854, 608.2834045290947, 609.283404648304, 610.2834047675133, 611.2834048867226, 612.2834050059319, 613.2834051251411, 614.2834052443504, 615.2834053635597, 616.283405482769, 617.2834056019783, 618.2834057211876, 619.2834058403969, 620.2834059596062, 621.2834060788155, 622.2834061980247, 623.283406317234, 624.2834064364433, 625.2834065556526, 626.2834066748619, 627.2834067940712, 628.2834069132805, 629.2834070324898, 630.2834071516991, 631.2834072709084, 632.2834073901176, 633.2834075093269, 634.2834076285362, 635.2834077477455, 636.2834078669548, 637.2834079861641, 639.2834082245827, 640.283408343792, 641.2834084630013, 642.2834085822105, 643.2834087014198, 644.2834088206291, 645.2834089398384, 646.2834090590477, 647.283409178257, 648.2834092974663, 649.2834094166756, 650.2834095358849, 651.2834096550941, 652.2833945155144, 653.2833946347237, 654.283394753933, 655.2833948731422, 656.2833949923515, 657.2833951115608, 658.2833952307701, 659.2833953499794, 660.2833954691887, 661.283395588398, 662.2833957076073, 663.2833958268166, 664.2833959460258, 665.2833960652351, 666.2833961844444, 667.2833963036537, 668.283396422863, 669.2833965420723, 670.2833966612816, 671.2833967804909, 672.2833968997002, 673.2833970189095, 674.2833971381187, 675.283397257328, 676.2833973765373, 677.2833974957466, 678.2833976149559, 679.2833977341652, 680.2833978533745, 681.2833979725838, 682.2834057211876, 683.2834058403969, 684.2834059596062, 685.2834060788155, 686.2834061980247, 687.283406317234, 688.2834064364433, 689.2834065556526, 690.2834066748619, 691.2834067940712, 692.2834069132805, 693.2834070324898, 694.2834071516991, 695.2834072709084, 696.2834073901176, 697.2834075093269, 698.2834076285362, 699.2834077477455, 700.2834078669548, 701.2834079861641, 702.2834081053734, 703.2834082245827, 704.283408343792, 705.2834084630013, 706.2834085822105, 707.2834087014198, 708.2834088206291, 709.2834089398384, 710.2834090590477, 711.283409178257, 712.2834016680717, 713.283401787281, 714.2834019064903, 715.2834020256996, 716.2834021449089, 717.2834022641182, 718.2834023833275, 719.2834025025368, 720.2834026217461, 721.2834027409554, 722.2815870046616, 723.2815870046616, 724.2815870046616, 725.2815870046616, 726.2815870046616, 727.2815870046616, 728.2815870046616, 729.2815870046616, 730.2815870046616, 731.2815870046616, 732.2815870046616, 733.2815870046616, 734.2815870046616, 735.2815870046616, 736.2815870046616, 737.2815870046616, 738.2815870046616, 739.2815870046616, 740.2815870046616, 741.2815870046616, 742.2815870046616, 743.2815870046616, 744.2815870046616, 745.2815870046616, 746.2815870046616, 747.2815870046616, 748.2815870046616, 749.2815870046616, 750.2815870046616, 751.2815870046616, 752.2815870046616, 753.2815870046616, 754.2815870046616, 755.2815870046616, 756.2815870046616, 757.2815870046616, 758.2815870046616, 759.2815870046616, 760.2815870046616 ], "terminate_on_failure": false }, "OutsideRouteLanesTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "FAILURE", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 35.22, "optional": false, "_current_index": 760, "_route_length": 762, "_outside_lane_active": true, "_wrong_lane_active": true, "_last_road_id": 15, "_last_lane_id": -1, "_total_distance": 759.2815870046616, "_wrong_distance": 0, "terminate_on_failure": false }, "RunningRedLightTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "FAILURE", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 3, "optional": false, "_last_red_light_id": 288, "debug": false, "terminate_on_failure": false }, "RunningStopTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "SUCCESS", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 0, "optional": false, "list_traffic_events": [], "_list_stop_signs": [], "_target_stop_sign": null, "_stop_completed": false, "_affected_by_stop": false, "terminate_on_failure": false }, "ActorSpeedAboveThresholdTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": true, "test_status": "SUCCESS", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 0, "optional": false, "list_traffic_events": [], "_speed_threshold": 0.1, "_below_threshold_max_time": 90.0, "_time_last_valid_state": 70.80000105500221, "terminate_on_failure": false } } ================================================ FILE: scenario_runner/srunner/metrics/data/DistanceBetweenVehicles_criteria.json ================================================ { "CollisionTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "SUCCESS", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 0, "optional": false, "list_traffic_events": [], "_collision_sensor": null, "other_actor": null, "other_actor_type": null, "registered_collisions": [], "last_id": null, "collision_time": null, "terminate_on_failure": false } } ================================================ FILE: scenario_runner/srunner/metrics/data/DistanceToLaneCenter_criteria.json ================================================ { "CollisionTest": { "children": [], "feedback_message": "", "blackbox_level": 4, "_terminate_on_failure": false, "test_status": "SUCCESS", "expected_value_success": 0, "expected_value_acceptable": null, "actual_value": 0, "optional": false, "list_traffic_events": [], "_collision_sensor": null, "other_actor": null, "other_actor_type": null, "registered_collisions": [], "last_id": null, "collision_time": null, "terminate_on_failure": false } } ================================================ FILE: scenario_runner/srunner/metrics/examples/basic_metric.py ================================================ #!/usr/bin/env python # 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 . """ This module provide BasicMetric, the basic class of all the metrics. """ class BasicMetric(object): """ Base class of all the metrics. """ def __init__(self, town_map, log, criteria=None): """ Initialization of the metric class. This calls the metrics log and creates the metrics Args: town_map (carla.Map): Map of the simulation. Used to access the Waypoint API. log (srunner.metrics.tools.Metricslog): instance of a class used to access the recorder information criteria (dict): list of dictionaries with all the criteria information """ # Create the metrics of the simulation. This part is left to the user self._create_metric(town_map, log, criteria) def _create_metric(self, town_map, log, criteria): """ Pure virtual function to setup the metrics by the user. Args: town_map (carla.Map): Map of the simulation. Used to access the Waypoint API. log (srunner.metrics.tools.Metricslog): instance of a class used to access the recorder information criteria (dict): dictionaries with all the criteria information """ raise NotImplementedError( "This function should be re-implemented by all metrics" "If this error becomes visible the class hierarchy is somehow broken") ================================================ FILE: scenario_runner/srunner/metrics/examples/criteria_filter.py ================================================ #!/usr/bin/env python # 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 . """ This metric filters the useful information of the criteria (sucess / fail ...), and dump it into a json file It is meant to serve as an example of how to use the criteria """ import json from srunner.metrics.examples.basic_metric import BasicMetric class CriteriaFilter(BasicMetric): """ Metric class CriteriaFilter """ def _create_metric(self, town_map, log, criteria): """ Implementation of the metric. This is an example to show how to use the criteria """ ### Parse the criteria information, filtering only the useful information, and dump it into a json ### results = {} for criterion_name in criteria: criterion = criteria[criterion_name] results.update({criterion_name: { "test_status": criterion["test_status"], "actual_value": criterion["actual_value"], "success_value": criterion["expected_value_success"] } } ) with open('srunner/metrics/data/CriteriaFilter_results.json', 'w') as fw: json.dump(results, fw, sort_keys=False, indent=4) ================================================ FILE: scenario_runner/srunner/metrics/examples/distance_between_vehicles.py ================================================ #!/usr/bin/env python # 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 . """ This metric calculates the distance between the ego vehicle and another actor, dumping it to a json file. It is meant to serve as an example of how to use the information from the recorder """ import math import matplotlib.pyplot as plt from srunner.metrics.examples.basic_metric import BasicMetric class DistanceBetweenVehicles(BasicMetric): """ Metric class DistanceBetweenVehicles """ def _create_metric(self, town_map, log, criteria): """ Implementation of the metric. This is an example to show how to use the recorder, accessed via the log. """ # Get the ID of the two vehicles ego_id = log.get_ego_vehicle_id() adv_id = log.get_actor_ids_with_role_name("scenario")[0] # Could have also used its type_id dist_list = [] frames_list = [] # Get the frames both actors were alive start_ego, end_ego = log.get_actor_alive_frames(ego_id) start_adv, end_adv = log.get_actor_alive_frames(adv_id) start = max(start_ego, start_adv) end = min(end_ego, end_adv) # Get the distance between the two for i in range(start, end): # Get the transforms ego_location = log.get_actor_transform(ego_id, i).location adv_location = log.get_actor_transform(adv_id, i).location # Filter some points for a better graph if adv_location.z < -10: continue dist_v = ego_location - adv_location dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z) dist_list.append(dist) frames_list.append(i) # Use matplotlib to show the results plt.plot(frames_list, dist_list) plt.ylabel('Distance [m]') plt.xlabel('Frame number') plt.title('Distance between the ego vehicle and the adversary over time') plt.show() ================================================ FILE: scenario_runner/srunner/metrics/examples/distance_to_lane_center.py ================================================ #!/usr/bin/env python # 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 . """ This metric calculates the distance between the ego vehicle and the center of the lane, dumping it to a json file. It is meant to serve as an example of how to use the map API """ import math import json from srunner.metrics.examples.basic_metric import BasicMetric class DistanceToLaneCenter(BasicMetric): """ Metric class DistanceToLaneCenter """ def _create_metric(self, town_map, log, criteria): """ Implementation of the metric. """ # Get ego vehicle id ego_id = log.get_ego_vehicle_id() dist_list = [] frames_list = [] # Get the frames the ego actor was alive and its transforms start, end = log.get_actor_alive_frames(ego_id) # Get the projected distance vector to the center of the lane for i in range(start, end + 1): ego_location = log.get_actor_transform(ego_id, i).location ego_waypoint = town_map.get_waypoint(ego_location) # Get the distance vector and project it a = ego_location - ego_waypoint.transform.location # Ego to waypoint vector b = ego_waypoint.transform.get_right_vector() # Waypoint perpendicular vector b_norm = math.sqrt(b.x * b.x + b.y * b.y + b.z * b.z) ab_dot = a.x * b.x + a.y * b.y + a.z * b.z dist_v = ab_dot/(b_norm*b_norm)*b dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z) # Get the sign of the distance (left side is positive) c = ego_waypoint.transform.get_forward_vector() # Waypoint forward vector ac_cross = c.x * a.y - c.y * a.x if ac_cross < 0: dist *= -1 dist_list.append(dist) frames_list.append(i) # Save the results to a file results = {'frames': frames_list, 'distance': dist_list} with open('srunner/metrics/data/DistanceToLaneCenter_results.json', 'w') as fw: json.dump(results, fw, sort_keys=False, indent=4) ================================================ FILE: scenario_runner/srunner/metrics/tools/metrics_log.py ================================================ #!/usr/bin/env python # 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 . """ Support class of the MetricsManager to query the information available to the metrics. It also provides a series of functions to help the user querry specific information """ import fnmatch from srunner.metrics.tools.metrics_parser import MetricsParser class MetricsLog(object): # pylint: disable=too-many-public-methods """ Utility class to query the log. """ def __init__(self, recorder): """ Initializes the log class and parses it to extract the dictionaries. """ # Parse the information parser = MetricsParser(recorder) self._simulation, self._actors, self._frames = parser.parse_recorder_info() ### Functions used to get general info of the simulation ### def get_actor_collisions(self, actor_id): """ Returns a dict where the keys are the frame number and the values, a list of actor ids the actor collided with. Args: actor_id (int): ID of the actor. """ actor_collisions = {} for i, frame in enumerate(self._frames): collisions = frame["events"]["collisions"] if actor_id in collisions: actor_collisions.update({i: collisions[actor_id]}) return actor_collisions def get_total_frame_count(self): """ Returns an int with the total amount of frames the simulation lasted. """ return self._simulation["total_frames"] def get_elapsed_time(self, frame): """ Returns a float with the elapsed time of a specific frame. """ return self._frames[frame]["frame"]["elapsed_time"] def get_delta_time(self, frame): """ Returns a float with the delta time of a specific frame. """ return self._frames[frame]["frame"]["delta_time"] def get_platform_time(self, frame): """ Returns a float with the platform time time of a specific frame. """ return self._frames[frame]["frame"]["platform_time"] ### Functions used to get info about the actors ### def get_ego_vehicle_id(self): """ Returns the id of the ego vehicle. """ return self.get_actor_ids_with_role_name("hero")[0] def get_actor_ids_with_role_name(self, role_name): """ Returns a list of actor ids that match the given role_name. Args: role_name (str): string with the desired role_name to filter the actors. """ actor_list = [] for actor_id in self._actors: actor = self._actors[actor_id] if "role_name" in actor and actor["role_name"] == role_name: actor_list.append(actor_id) return actor_list def get_actor_ids_with_type_id(self, type_id): """ Returns a list of actor ids that match the given type_id, matching fnmatch standard. Args: type_id (str): string with the desired type id to filter the actors. """ actor_list = [] for actor_id in self._actors: actor = self._actors[actor_id] if "type_id" in actor and fnmatch.fnmatch(actor["type_id"], type_id): actor_list.append(actor_id) return actor_list def get_actor_attributes(self, actor_id): """ Returns a dictionary with all the attributes of an actor. Args: actor_id (int): ID of the actor. """ if actor_id in self._actors: return self._actors[actor_id] return None def get_actor_bounding_box(self, actor_id): """ Returns the bounding box of the specified actor Args: actor_id (int): Id of the actor """ if actor_id in self._actors: if "bounding_box" in self._actors[actor_id]: return self._actors[actor_id]["bounding_box"] return None return None def get_traffic_light_trigger_volume(self, traffic_light_id): """ Returns the trigger volume of the specified traffic light Args: actor_id (int): Id of the traffic light """ if traffic_light_id in self._actors: if "trigger_volume" in self._actors[traffic_light_id]: return self._actors[traffic_light_id]["trigger_volume"] return None return None def get_actor_alive_frames(self, actor_id): """ Returns a tuple with the first and last frame an actor was alive. It is important to note that frames start at 1, not 0. Args: actor_id (int): Id of the actor """ if actor_id in self._actors: actor_info = self._actors[actor_id] first_frame = actor_info["created"] if "destroyed" in actor_info: last_frame = actor_info["destroyed"] - 1 else: last_frame = self.get_total_frame_count() return first_frame, last_frame return None, None ### Functions used to get the actor states ### def _get_actor_state(self, actor_id, state, frame): """ Given an actor id, returns the specific variable of that actor at a given frame. Returns None if the actor_id or the state are missing. Args: actor_id (int): Id of the actor to be checked. frame: (int): frame number of the simulation. attribute (str): name of the actor's attribute to be returned. """ frame_state = self._frames[frame - 1]["actors"] # Check if the actor exists if actor_id in frame_state: # Check if the state exists if state not in frame_state[actor_id]: return None state_info = frame_state[actor_id][state] return state_info return None def _get_all_actor_states(self, actor_id, state, first_frame=None, last_frame=None): """ Given an actor id, returns a list of the specific variable of that actor during a frame interval. Some elements might be None. By default, first_frame and last_frame are the start and end of the simulation, respectively. Args: actor_id (int): ID of the actor. attribute: name of the actor's attribute to be returned. first_frame (int): First frame checked. By default, 0. last_frame (int): Last frame checked. By default, max number of frames. """ if first_frame is None: first_frame = 1 if last_frame is None: last_frame = self.get_total_frame_count() state_list = [] for frame_number in range(first_frame, last_frame + 1): state_info = self._get_actor_state(actor_id, state, frame_number) state_list.append(state_info) return state_list def _get_states_at_frame(self, frame, state, actor_list=None): """ Returns a dict where the keys are the frame number, and the values are the carla.Transform of the actor at the given frame. By default, all actors will be considered. """ states = {} actor_info = self._frames[frame]["actors"] for actor_id in actor_info: if not actor_list: _state = self._get_actor_state(actor_id, state, frame) if _state: states.update({actor_id: _state}) elif actor_id in actor_list: _state = self._get_actor_state(actor_id, state, frame) states.update({actor_id: _state}) return states # Transforms def get_actor_transform(self, actor_id, frame): """ Returns the transform of the actor at a given frame. """ return self._get_actor_state(actor_id, "transform", frame) def get_all_actor_transforms(self, actor_id, first_frame=None, last_frame=None): """ Returns a list with all the transforms of the actor at the frame interval. """ return self._get_all_actor_states(actor_id, "transform", first_frame, last_frame) def get_actor_transforms_at_frame(self, frame, actor_list=None): """ Returns a dictionary {int - carla.Transform} with the actor ID and transform at a given frame of all the actors at actor_list. """ return self._get_states_at_frame(frame, "transform", actor_list) # Velocities def get_actor_velocity(self, actor_id, frame): """ Returns the velocity of the actor at a given frame. """ return self._get_actor_state(actor_id, "velocity", frame) def get_all_actor_velocities(self, actor_id, first_frame=None, last_frame=None): """ Returns a list with all the velocities of the actor at the frame interval. """ return self._get_all_actor_states(actor_id, "velocity", first_frame, last_frame) def get_actor_velocities_at_frame(self, frame, actor_list=None): """ Returns a dictionary {int - carla.Vector3D} with the actor ID and velocity at a given frame of all the actors at actor_list. """ return self._get_states_at_frame(frame, "velocity", actor_list) # Angular velocities def get_actor_angular_velocity(self, actor_id, frame): """ Returns the angular velocity of the actor at a given frame. """ return self._get_actor_state(actor_id, "angular_velocity", frame) def get_all_actor_angular_velocities(self, actor_id, first_frame=None, last_frame=None): """ Returns a list with all the angular velocities of the actor at the frame interval. """ return self._get_all_actor_states(actor_id, "angular_velocity", first_frame, last_frame) def get_actor_angular_velocities_at_frame(self, frame, actor_list=None): """ Returns a dictionary {int - carla.Vector3D} with the actor ID and angular velocity at a given frame of all the actors at actor_list. """ return self._get_states_at_frame(frame, "angular_velocity", actor_list) # Acceleration def get_actor_acceleration(self, actor_id, frame): """ Returns the acceleration of the actor at a given frame. """ return self._get_actor_state(actor_id, "acceleration", frame) def get_all_actor_accelerations(self, actor_id, first_frame=None, last_frame=None): """ Returns a list with all the accelerations of the actor at the frame interval. """ return self._get_all_actor_states(actor_id, "acceleration", first_frame, last_frame) def get_actor_accelerations_at_frame(self, frame, actor_list=None): """ Returns a dictionary {int - carla.Vector3D} with the actor ID and angular velocity at a given frame of all the actors at actor_list. """ return self._get_states_at_frame(frame, "acceleration", actor_list) # Controls def get_vehicle_control(self, vehicle_id, frame): """ Returns the control of the vehicle at a given frame. """ return self._get_actor_state(vehicle_id, "control", frame) def get_vehicle_physics_control(self, vehicle_id, frame): """ Returns the carla.VehiclePhysicsControl of a vehicle at a given frame. Returns None if the id can't be found. """ for i in range(frame - 1, -1, -1): # Go backwards from the frame until 0 physics_info = self._frames[i]["events"]["physics_control"] if vehicle_id in physics_info: return physics_info[vehicle_id] return None def get_walker_speed(self, walker_id, frame): """ Returns the speed of the walker at a specific frame. """ return self._get_actor_state(walker_id, "speed", frame) # Traffic lights def get_traffic_light_state(self, traffic_light_id, frame): """ Returns the state of the traffic light at a specific frame. """ return self._get_actor_state(traffic_light_id, "state", frame) def is_traffic_light_frozen(self, traffic_light_id, frame): """ Returns whether or not the traffic light is frozen at a specific frame. """ return self._get_actor_state(traffic_light_id, "frozen", frame) def get_traffic_light_elapsed_time(self, traffic_light_id, frame): """ Returns the elapsed time of the traffic light at a specific frame. """ return self._get_actor_state(traffic_light_id, "elapsed_time", frame) def get_traffic_light_state_time(self, traffic_light_id, state, frame): """ Returns the state time of the traffic light at a specific frame. Returns None if the id can't be found. """ for i in range(frame - 1, -1, -1): # Go backwards from the frame until 0 state_times_info = self._frames[i]["events"]["traffic_light_state_time"] if traffic_light_id in state_times_info: states = state_times_info[traffic_light_id] if state in states: return state_times_info[traffic_light_id][state] return None # Vehicle lights def get_vehicle_lights(self, vehicle_id, frame): """ Returns the vehicle lights of the vehicle at a specific frame. """ return self._get_actor_state(vehicle_id, "lights", frame) def is_vehicle_light_active(self, light, vehicle_id, frame): """ Returns the elapsed time of the traffic light at a specific frame. """ lights = self.get_vehicle_lights(vehicle_id, frame) if light in lights: return True return False # Scene lights def get_scene_light_state(self, light_id, frame): """ Returns the state of the scene light at a specific frame. Returns None if the id can't be found. """ for i in range(frame - 1, -1, -1): # Go backwards from the frame until 0 scene_lights_info = self._frames[i]["events"]["scene_lights"] if light_id in scene_lights_info: return scene_lights_info[light_id] return None ================================================ FILE: scenario_runner/srunner/metrics/tools/metrics_parser.py ================================================ #!/usr/bin/env python # 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 . """ Support class of the MetricsManager to parse the information of the CARLA recorder into a readable dictionary """ import carla def parse_actor(info): """ Returns a dictionary with the basic actor information Args: info (list): list corresponding to a row of the recorder """ actor = { "type_id": info[2], "location": carla.Location( float(info[5][1:-1]) / 100, float(info[6][:-1]) / 100, float(info[7][:-1]) / 100 ) } return actor def parse_transform(info): """ Parses a list into a carla.Transform Args: info (list): list corresponding to a row of the recorder """ transform = carla.Transform( carla.Location( float(info[3][1:-1]) / 100, float(info[4][:-1]) / 100, float(info[5][:-1]) / 100, ), carla.Rotation( float(info[8][:-1]), # pitch float(info[9][:-1]), # yaw float(info[7][1:-1]) # roll ) ) return transform def parse_control(info): """ Parses a list into a carla.VehicleControl Args: info (list): list corresponding to a row of the recorder """ control = carla.VehicleControl( float(info[5]), # throttle float(info[3]), # steer float(info[7]), # brake bool(int(info[9])), # hand_brake int(info[11]) < 0, # reverse False, # manual_gear_shift int(info[11]), # gear ) return control def parse_vehicle_lights(info): """ Parses a list into a carla.VehicleLightState Args: info (list): list corresponding to a row of the recorder """ srt_to_vlight = { "None": carla.VehicleLightState.NONE, "Position": carla.VehicleLightState.Position, "LowBeam": carla.VehicleLightState.LowBeam, "HighBeam": carla.VehicleLightState.HighBeam, "Brake": carla.VehicleLightState.Brake, "RightBlinker": carla.VehicleLightState.RightBlinker, "LeftBlinker": carla.VehicleLightState.LeftBlinker, "Reverse": carla.VehicleLightState.Reverse, "Fog": carla.VehicleLightState.Fog, "Interior": carla.VehicleLightState.Interior, "Special1": carla.VehicleLightState.Special1, "Special2": carla.VehicleLightState.Special2, } lights = [] for i in range(2, len(info)): lights.append(srt_to_vlight[info[i]]) return lights def parse_traffic_light(info): """ Parses a list into a dictionary with all the traffic light's information Args: info (list): list corresponding to a row of the recorder """ number_to_state = { "0": carla.TrafficLightState.Red, "1": carla.TrafficLightState.Yellow, "2": carla.TrafficLightState.Green, "3": carla.TrafficLightState.Off, "4": carla.TrafficLightState.Unknown, } traffic_light = { "state": number_to_state[info[3]], "frozen": bool(int(info[5])), "elapsed_time": float(info[7]), } return traffic_light def parse_velocity(info): """ Parses a list into a carla.Vector3D with the velocity Args: info (list): list corresponding to a row of the recorder """ velocity = carla.Vector3D( float(info[3][1:-1]), float(info[4][:-1]), float(info[5][:-1]) ) return velocity def parse_angular_velocity(info): """ Parses a list into a carla.Vector3D with the angular velocity Args: info (list): list corresponding to a row of the recorder """ velocity = carla.Vector3D( float(info[7][1:-1]), float(info[8][:-1]), float(info[9][:-1]) ) return velocity def parse_scene_lights(info): """ Parses a list into a carla.VehicleLightState Args: info (list): list corresponding to a row of the recorder """ red = int(float(info[7][1:-1]) * 255) green = int(float(info[8][:-1]) * 255) blue = int(float(info[9][:-1]) * 255) scene_light = carla.LightState( int(float(info[5])), carla.Color(red, green, blue), carla.LightGroup.NONE, bool(info[3]) ) return scene_light def parse_bounding_box(info): """ Parses a list into a carla.BoundingBox Args: info (list): list corresponding to a row of the recorder """ location = carla.Location( float(info[3][1:-1])/100, float(info[4][:-1])/100, float(info[5][:-1])/100, ) extent = carla.Vector3D( float(info[7][1:-1])/100, float(info[8][:-1])/100, float(info[9][:-1])/100, ) bbox = carla.BoundingBox(location, extent) return bbox def parse_state_times(info): """ Parses a list into a dict containing the state times of the traffic lights Args: info (list): list corresponding to a row of the recorder """ state_times = { carla.TrafficLightState.Green: float(info[3]), carla.TrafficLightState.Yellow: float(info[5]), carla.TrafficLightState.Red: float(info[7]), } return state_times def parse_vector_list(info): """ Parses a list of string into a list of Vector2D Args: info (list): list corresponding to a row of the recorder """ vector_list = [] for i in range(0, len(info), 2): vector = carla.Vector2D( float(info[i][1:-1]), float(info[i+1][:-1]), ) vector_list.append(vector) return vector_list def parse_gears_control(info): """ Parses a list into a GearPhysicsControl Args: info (list): list corresponding to a row of the recorder """ gears_control = carla.GearPhysicsControl( float(info[3]), float(info[5]), float(info[7]), ) return gears_control def parse_wheels_control(info): """ Parses a list into a WheelsPhysicsControl Args: info (list): list corresponding to a row of the recorder """ gears_control = carla.WheelPhysicsControl( float(info[3]), float(info[5]), float(info[7]), float(info[9]), float(info[11]), float(info[13]), carla.Vector3D() ) return gears_control class MetricsParser(object): """ Class used to parse the CARLA recorder into readable information """ def __init__(self, recorder_info): self.recorder_info = recorder_info self.frame_list = None self.frame_row = None self.i = 0 def get_row_elements(self, indent_num, split_string): """ returns a list with the elements of the row """ return self.frame_row[indent_num:].split(split_string) def next_row(self): """ Gets the next row of the recorder """ self.i += 1 self.frame_row = self.frame_list[self.i] def parse_recorder_info(self): """ Parses the recorder into readable information. Args: recorder_info (str): string given by the recorder """ # Divide it into frames recorder_list = self.recorder_info.split("Frame") # Get general information header = recorder_list[0].split("\n") sim_map = header[1][5:] sim_date = header[2][6:] annex = recorder_list[-1].split("\n") sim_frames = int(annex[0][3:]) sim_duration = float(annex[1][10:-8]) recorder_list = recorder_list[1:-1] simulation_info = { "map": sim_map, "date:": sim_date, "total_frames": sim_frames, "duration": sim_duration } actors_info = {} frames_info = [] for frame in recorder_list: # Divide the frame in lines self.frame_list = frame.split("\n") # Get the general frame information frame_info = self.frame_list[0].split(" ") frame_number = int(frame_info[1]) frame_time = float(frame_info[3]) try: prev_frame = frames_info[frame_number - 2] prev_time = prev_frame["frame"]["elapsed_time"] delta_time = round(frame_time - prev_time, 6) except IndexError: delta_time = 0 # Variable to store all the information about the frame frame_state = { "frame": { "elapsed_time": frame_time, "delta_time": delta_time, "platform_time": None }, "actors": {}, "events":{ "scene_lights": {}, "physics_control": {}, "traffic_light_state_time": {}, "collisions": {} } } # Loop through all the other rows. self.i = 0 self.next_row() while self.frame_row.startswith(' Create') or self.frame_row.startswith(' '): if self.frame_row.startswith(' Create'): elements = self.get_row_elements(1, " ") actor_id = int(elements[1][:-1]) actor = parse_actor(elements) actors_info.update({actor_id: actor}) actors_info[actor_id].update({"created": frame_number}) else: elements = self.get_row_elements(2, " = ") actors_info[actor_id].update({elements[0]: elements[1]}) self.next_row() while self.frame_row.startswith(' Destroy'): elements = self.get_row_elements(1, " ") actor_id = int(elements[1]) actors_info[actor_id].update({"destroyed": frame_number}) self.next_row() while self.frame_row.startswith(' Collision'): elements = self.get_row_elements(1, " ") actor_id = int(elements[4]) other_id = int(elements[-1]) if actor_id not in frame_state["events"]["collisions"]: frame_state["events"]["collisions"][actor_id] = [other_id] else: collisions = frame_state["events"]["collisions"][actor_id] collisions.append(other_id) frame_state["events"]["collisions"].update({actor_id: collisions}) self.next_row() while self.frame_row.startswith(' Parenting'): elements = self.get_row_elements(1, " ") actor_id = int(elements[1]) parent_id = int(elements[3]) actors_info[actor_id].update({"parent": parent_id}) self.next_row() if self.frame_row.startswith(' Positions'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) transform = parse_transform(elements) frame_state["actors"].update({actor_id: {"transform": transform}}) self.next_row() if self.frame_row.startswith(' State traffic lights'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) traffic_light = parse_traffic_light(elements) frame_state["actors"].update({actor_id: traffic_light}) self.next_row() if self.frame_row.startswith(' Vehicle animations'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) control = parse_control(elements) frame_state["actors"][actor_id].update({"control": control}) self.next_row() if self.frame_row.startswith(' Walker animations'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) frame_state["actors"][actor_id].update({"speed": elements[3]}) self.next_row() if self.frame_row.startswith(' Vehicle light animations'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) lights = parse_vehicle_lights(elements) frame_state["actors"][actor_id].update({"lights": lights}) self.next_row() if self.frame_row.startswith(' Scene light changes'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) scene_light = parse_scene_lights(elements) frame_state["events"]["scene_lights"].update({actor_id: scene_light}) self.next_row() if self.frame_row.startswith(' Dynamic actors'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) velocity = parse_velocity(elements) frame_state["actors"][actor_id].update({"velocity": velocity}) angular_v = parse_angular_velocity(elements) frame_state["actors"][actor_id].update({"angular_velocity": angular_v}) if delta_time == 0: acceleration = carla.Vector3D(0, 0, 0) else: prev_velocity = frame_state["actors"][actor_id]["velocity"] acceleration = (velocity - prev_velocity) / delta_time frame_state["actors"][actor_id].update({"acceleration": acceleration}) self.next_row() if self.frame_row.startswith(' Actor bounding boxes'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) bbox = parse_bounding_box(elements) actors_info[actor_id].update({"bounding_box": bbox}) self.next_row() if self.frame_row.startswith(' Actor trigger volumes'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) trigvol = parse_bounding_box(elements) actors_info[actor_id].update({"trigger_volume": trigvol}) self.next_row() if self.frame_row.startswith(' Current platform time'): elements = self.get_row_elements(1, " ") platform_time = float(elements[-1]) frame_state["frame"]["platform_time"] = platform_time self.next_row() if self.frame_row.startswith(' Physics Control'): self.next_row() actor_id = None while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) physics_control = carla.VehiclePhysicsControl() self.next_row() forward_gears = [] wheels = [] while self.frame_row.startswith(' '): if self.frame_row.startswith(' '): elements = self.get_row_elements(4, " ") if elements[0] == "gear": forward_gears.append(parse_gears_control(elements)) elif elements[0] == "wheel": wheels.append(parse_wheels_control(elements)) else: elements = self.get_row_elements(3, " = ") name = elements[0] if name == "center_of_mass": values = elements[1].split(" ") value = carla.Vector3D( float(values[0][1:-1]), float(values[1][:-1]), float(values[2][:-1]), ) setattr(physics_control, name, value) elif name == "torque_curve" or name == "steering_curve": values = elements[1].split(" ") value = parse_vector_list(values) setattr(physics_control, name, value) elif name == "use_gear_auto_box": name = "use_gear_autobox" value = True if elements[1] == "true" else False setattr(physics_control, name, value) elif "forward_gears" in name or "wheels" in name: pass else: name = name.lower() value = float(elements[1]) setattr(physics_control, name, value) self.next_row() setattr(physics_control, "forward_gears", forward_gears) setattr(physics_control, "wheels", wheels) frame_state["events"]["physics_control"].update({actor_id: physics_control}) if self.frame_row.startswith(' Traffic Light time events'): self.next_row() while self.frame_row.startswith(' '): elements = self.get_row_elements(2, " ") actor_id = int(elements[1]) state_times = parse_state_times(elements) frame_state["events"]["traffic_light_state_time"].update({actor_id: state_times}) self.next_row() frames_info.append(frame_state) return simulation_info, actors_info, frames_info ================================================ FILE: scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_Catalog.xsd ================================================ XML Schema Definition for OpenSCENARIO Catalog XML files - Version Draft 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany ================================================ FILE: scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_TypeDefs.xsd ================================================ XML Schema Type Definitions for OpenSCENARIO XML files - Version Draft 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany ================================================ FILE: scenario_runner/srunner/openscenario/0.9.x/OpenSCENARIO_v0.9.1.xsd ================================================ XML Schema Definition for OpenSCENARIO XML files - Version 0.9.1, (c)2017 by VIRES Simulationstechnologie GmbH, Germany ================================================ FILE: scenario_runner/srunner/openscenario/0.9.x/migration0_9_1to1_0.xslt ================================================ longitudinal lateral cartesianDistance greaterThan lessThan equalTo none railing barrier endTransition stopTransition completeState risingOrFalling falling rising position follow WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog WARNING: OSCTrajectory is restructured and connot be automatically migrated. Review XML
WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog WARNING: Jam is desupported: removed during migration WARNING: Script is desupported: removed during migration WARNING: OSCPrivateAction.Meeting is desupported: removed during migration ERROR: Act: Cancel and End are both defined: Version 1.0 only supports Stop Trigger. Invalid XML is produced and needs to be revisited. WARNING: Storyboard.Story.Act.Sequence.Actors.ByCondition: "anyEntity" is de-supported for version 1.0 WARNING: OSCPrivateAction.Longitudinal.Speed or OSCPrivateAction.Lateral.LaneChange.Dynamics: Distance, time, rate must exclude each other in the original file. This results in a invalid output. WARNING: OSCPrivateAction.Longitudinal.Speed or OSCPrivateAction.Lateral.LaneChange.Dynamics: There must be at least one of time, rate or distance in the original file. This results in a invalid output. WARNING: Review catalogs since driver catalog and pedestrian catalogs are merged into controller catalog WARNING: Event.priority: 'following' is desupported: removed during migration. This results in unvalifd XML code. WARNING: OSCPrivateAction.Meeting is desupported: removed during migration: This may result in unvalid XML WARNING: Jam is desupported: removed during migration: This may result in unvalid XML WARNING: Script is desupported: removed during migration: This may result in unvalid XML Migration: Insert Controller here ERROR: OSCTrafficDefinition.DriverDistribution.Driver cannot be migrated automatically and will result in unvalid XML output. WARNING: OSCTrajectory.Vertex: OSCTrajectory is restructured and connot be automatically migrated. Review XML.
================================================ FILE: scenario_runner/srunner/openscenario/OpenSCENARIO.xsd ================================================  ================================================ FILE: scenario_runner/srunner/scenarioconfigs/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/scenarioconfigs/openscenario_configuration.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides the key configuration parameters for a scenario based on OpenSCENARIO """ import logging import os import xml.etree.ElementTree as ET import xmlschema import carla # pylint: disable=line-too-long from srunner.scenarioconfigs.scenario_configuration import ActorConfigurationData, ScenarioConfiguration # pylint: enable=line-too-long from srunner.scenariomanager.carla_data_provider import CarlaDataProvider # workaround from srunner.tools.openscenario_parser import OpenScenarioParser class OpenScenarioConfiguration(ScenarioConfiguration): """ Limitations: - Only one Story + Init is supported per Storyboard """ def __init__(self, filename, client): self.xml_tree = ET.parse(filename) self._filename = filename self._validate_openscenario_configuration() self.client = client self.catalogs = {} self.other_actors = [] self.ego_vehicles = [] self.trigger_points = [] self.weather = carla.WeatherParameters() self.storyboard = self.xml_tree.find("Storyboard") self.story = self.storyboard.find("Story") self.init = self.storyboard.find("Init") logging.basicConfig() self.logger = logging.getLogger("[SR:OpenScenarioConfiguration]") self._global_parameters = {} self._set_parameters() self._parse_openscenario_configuration() def _validate_openscenario_configuration(self): """ Validate the given OpenSCENARIO config against the 0.9.1 XSD Note: This will throw if the config is not valid. But this is fine here. """ xsd_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), "../openscenario/OpenSCENARIO.xsd") xsd = xmlschema.XMLSchema(xsd_file) xsd.validate(self.xml_tree) def _validate_openscenario_catalog_configuration(self, catalog_xml_tree): """ Validate the given OpenSCENARIO catalog config against the 0.9.1 XSD Note: This will throw if the catalog config is not valid. But this is fine here. """ xsd_file = os.path.join(os.path.dirname(os.path.abspath(__file__)), "../openscenario/OpenSCENARIO.xsd") xsd = xmlschema.XMLSchema(xsd_file) xsd.validate(catalog_xml_tree) def _parse_openscenario_configuration(self): """ Parse the given OpenSCENARIO config file, set and validate parameters """ OpenScenarioParser.set_osc_filepath(os.path.dirname(self._filename)) self._check_version() self._load_catalogs() self._set_scenario_name() self._set_carla_town() self._set_actor_information() self._validate_result() def _check_version(self): """ Ensure correct OpenSCENARIO version is used """ header = self.xml_tree.find("FileHeader") if not (header.attrib.get('revMajor') == "1" and header.attrib.get('revMinor') == "0"): raise AttributeError("Only OpenSCENARIO 1.0 is supported") def _load_catalogs(self): """ Read Catalog xml files into dictionary for later use NOTE: Catalogs must have distinct names, even across different types """ catalogs = self.xml_tree.find("CatalogLocations") if list(catalogs) is None: return catalog_types = ["Vehicle", "Controller", "Pedestrian", "MiscObject", "Environment", "Maneuver", "Trajectory", "Route"] for catalog_type in catalog_types: catalog = catalogs.find(catalog_type + "Catalog") if catalog is None: continue catalog_path = catalog.find("Directory").attrib.get('path') + "/" + catalog_type + "Catalog.xosc" if not os.path.isabs(catalog_path) and "xosc" in self._filename: catalog_path = os.path.dirname(os.path.abspath(self._filename)) + "/" + catalog_path if not os.path.isfile(catalog_path): self.logger.warning(" The %s path for the %s Catalog is invalid", catalog_path, catalog_type) else: xml_tree = ET.parse(catalog_path) self._validate_openscenario_catalog_configuration(xml_tree) catalog = xml_tree.find("Catalog") catalog_name = catalog.attrib.get("name") self.catalogs[catalog_name] = {} for entry in catalog: self.catalogs[catalog_name][entry.attrib.get("name")] = entry def _set_scenario_name(self): """ Extract the scenario name from the OpenSCENARIO header information """ header = self.xml_tree.find("FileHeader") self.name = header.attrib.get('description', 'Unknown') if self.name.startswith("CARLA:"): OpenScenarioParser.set_use_carla_coordinate_system() def _set_carla_town(self): """ Extract the CARLA town (level) from the RoadNetwork information from OpenSCENARIO Note: The specification allows multiple Logics elements within the RoadNetwork element. Hence, there can be multiple towns specified. We just use the _last_ one. """ for logic in self.xml_tree.find("RoadNetwork").findall("LogicFile"): self.town = logic.attrib.get('filepath', None) if self.town is not None and ".xodr" in self.town: if not os.path.isabs(self.town): self.town = os.path.dirname(os.path.abspath(self._filename)) + "/" + self.town if not os.path.exists(self.town): raise AttributeError("The provided RoadNetwork '{}' does not exist".format(self.town)) # workaround for relative positions during init world = self.client.get_world() if world is None or world.get_map().name != self.town: self.logger.warning(" Wrong OpenDRIVE map in use. Forcing reload of CARLA world") if ".xodr" in self.town: with open(self.town) as od_file: data = od_file.read() self.client.generate_opendrive_world(str(data)) else: self.client.load_world(self.town) world = self.client.get_world() CarlaDataProvider.set_world(world) world.wait_for_tick() else: CarlaDataProvider.set_world(world) def _set_parameters(self): """ Parse the complete scenario definition file, and replace all parameter references with the actual values Set _global_parameters. """ self.xml_tree, self._global_parameters = OpenScenarioParser.set_parameters(self.xml_tree) for elem in self.xml_tree.iter(): if elem.find('ParameterDeclarations') is not None: elem, _ = OpenScenarioParser.set_parameters(elem) OpenScenarioParser.set_global_parameters(self._global_parameters) def _set_actor_information(self): """ Extract all actors and their corresponding specification NOTE: The rolename property has to be unique! """ for entity in self.xml_tree.iter("Entities"): for obj in entity.iter("ScenarioObject"): rolename = obj.attrib.get('name', 'simulation') args = dict() for prop in obj.iter("Property"): key = prop.get('name') value = prop.get('value') args[key] = value for catalog_reference in obj.iter("CatalogReference"): entry = OpenScenarioParser.get_catalog_entry(self.catalogs, catalog_reference) if entry.tag == "Vehicle": self._extract_vehicle_information(entry, rolename, entry, args) elif entry.tag == "Pedestrian": self._extract_pedestrian_information(entry, rolename, entry, args) elif entry.tag == "MiscObject": self._extract_misc_information(entry, rolename, entry, args) else: self.logger.error( " A CatalogReference specifies a reference that is not an Entity. Skipping...") for vehicle in obj.iter("Vehicle"): self._extract_vehicle_information(obj, rolename, vehicle, args) for pedestrian in obj.iter("Pedestrian"): self._extract_pedestrian_information(obj, rolename, pedestrian, args) for misc in obj.iter("MiscObject"): self._extract_misc_information(obj, rolename, misc, args) # Set transform for all actors # This has to be done in a multi-stage loop to resolve relative position settings all_actor_transforms_set = False while not all_actor_transforms_set: all_actor_transforms_set = True for actor in self.other_actors + self.ego_vehicles: if actor.transform is None: try: actor.transform = self._get_actor_transform(actor.rolename) except AttributeError as e: if "Object '" in str(e): ref_actor_rolename = str(e).split('\'')[1] for ref_actor in self.other_actors + self.ego_vehicles: if ref_actor.rolename == ref_actor_rolename: if ref_actor.transform is not None: raise e break if actor.transform is None: all_actor_transforms_set = False def _extract_vehicle_information(self, obj, rolename, vehicle, args): """ Helper function to _set_actor_information for getting vehicle information from XML tree """ color = None model = vehicle.attrib.get('name', "vehicle.*") category = vehicle.attrib.get('vehicleCategory', "car") ego_vehicle = False for prop in obj.iter("Property"): if prop.get('name', '') == 'type': ego_vehicle = prop.get('value') == 'ego_vehicle' if prop.get('name', '') == 'color': color = prop.get('value') speed = self._get_actor_speed(rolename) new_actor = ActorConfigurationData( model, None, rolename, speed, color=color, category=category, args=args) if ego_vehicle: self.ego_vehicles.append(new_actor) else: self.other_actors.append(new_actor) def _extract_pedestrian_information(self, obj, rolename, pedestrian, args): """ Helper function to _set_actor_information for getting pedestrian information from XML tree """ model = pedestrian.attrib.get('model', "walker.*") speed = self._get_actor_speed(rolename) new_actor = ActorConfigurationData(model, None, rolename, speed, category="pedestrian", args=args) self.other_actors.append(new_actor) def _extract_misc_information(self, obj, rolename, misc, args): """ Helper function to _set_actor_information for getting vehicle information from XML tree """ category = misc.attrib.get('miscObjectCategory') if category == "barrier": model = "static.prop.streetbarrier" elif category == "guardRail": model = "static.prop.chainbarrier" else: model = misc.attrib.get('name') new_actor = ActorConfigurationData(model, None, rolename, category="misc", args=args) self.other_actors.append(new_actor) def _get_actor_transform(self, actor_name): """ Get the initial actor transform provided by the Init section Note: - The OpenScenario specification allows multiple definitions. We use the _first_ one - The OpenScenario specification allows different ways of specifying a position. We currently support the specification with absolute world coordinates and the relative positions RelativeWorld, RelativeObject and RelativeLane - When using relative positions the relevant reference point (e.g. transform of another actor) should be defined before! """ actor_transform = carla.Transform() actor_found = False for private_action in self.init.iter("Private"): if private_action.attrib.get('entityRef', None) == actor_name: if actor_found: # pylint: disable=line-too-long self.logger.warning( " Warning: The actor '%s' was already assigned an initial position. Overwriting pose!", actor_name) # pylint: enable=line-too-long actor_found = True for position in private_action.iter('Position'): transform = OpenScenarioParser.convert_position_to_transform( position, actor_list=self.other_actors + self.ego_vehicles) if transform: actor_transform = transform if not actor_found: # pylint: disable=line-too-long self.logger.warning( " Warning: The actor '%s' was not assigned an initial position. Using (0,0,0)", actor_name) # pylint: enable=line-too-long return actor_transform def _get_actor_speed(self, actor_name): """ Get the initial actor speed provided by the Init section """ actor_speed = 0 actor_found = False for private_action in self.init.iter("Private"): if private_action.attrib.get('entityRef', None) == actor_name: if actor_found: # pylint: disable=line-too-long self.logger.warning( " Warning: The actor '%s' was already assigned an initial speed. Overwriting inital speed!", actor_name) # pylint: enable=line-too-long actor_found = True for longitudinal_action in private_action.iter('LongitudinalAction'): for speed in longitudinal_action.iter('SpeedAction'): for target in speed.iter('SpeedActionTarget'): for absolute in target.iter('AbsoluteTargetSpeed'): speed = float(absolute.attrib.get('value', 0)) if speed >= 0: actor_speed = speed else: raise AttributeError( "Warning: Speed value of actor {} must be positive. Speed set to 0.".format(actor_name)) # pylint: disable=line-too-long return actor_speed def _validate_result(self): """ Check that the current scenario configuration is valid """ if not self.name: raise AttributeError("No scenario name found") if not self.town: raise AttributeError("CARLA level not defined") if not self.ego_vehicles: self.logger.warning(" No ego vehicles defined in scenario") ================================================ FILE: scenario_runner/srunner/scenarioconfigs/route_scenario_configuration.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides the key configuration parameters for a route-based scenario """ import carla from agents.navigation.local_planner import RoadOption from srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration class RouteConfiguration(object): """ This class provides the basic configuration for a route """ def __init__(self, route=None): self.data = route self.folder_name = None def parse_xml(self, node): """ Parse route config XML """ self.data = [] for waypoint in node.iter("waypoint"): x = float(waypoint.attrib.get('x', 0)) y = float(waypoint.attrib.get('y', 0)) z = float(waypoint.attrib.get('z', 0)) c = waypoint.attrib.get('connection', '') connection = RoadOption[c.split('.')[1]] self.data.append((carla.Location(x, y, z), connection)) class RouteScenarioConfiguration(ScenarioConfiguration): """ Basic configuration of a RouteScenario """ folder_name = None trajectory = None scenario_file = None ================================================ FILE: scenario_runner/srunner/scenarioconfigs/scenario_configuration.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides the key configuration parameters for an XML-based scenario """ import carla class ActorConfigurationData(object): """ This is a configuration base class to hold model and transform attributes """ def __init__(self, model, transform, rolename='other', speed=0, autopilot=False, random=False, color=None, category="car", args=None): self.model = model self.rolename = rolename self.transform = transform self.speed = speed self.autopilot = autopilot self.random_location = random self.color = color self.category = category self.args = args @staticmethod def parse_from_node(node, rolename): """ static method to initialize an ActorConfigurationData from a given ET tree """ model = node.attrib.get('model', 'vehicle.*') pos_x = float(node.attrib.get('x', 0)) pos_y = float(node.attrib.get('y', 0)) pos_z = float(node.attrib.get('z', 0)) yaw = float(node.attrib.get('yaw', 0)) transform = carla.Transform(carla.Location(x=pos_x, y=pos_y, z=pos_z), carla.Rotation(yaw=yaw)) rolename = node.attrib.get('rolename', rolename) speed = node.attrib.get('speed', 0) autopilot = False if 'autopilot' in node.keys(): autopilot = True random_location = False if 'random_location' in node.keys(): random_location = True color = node.attrib.get('color', None) return ActorConfigurationData(model, transform, rolename, speed, autopilot, random_location, color) class ScenarioConfiguration(object): """ This class provides a basic scenario configuration incl.: - configurations for all actors - town, where the scenario should be executed - name of the scenario (e.g. ControlLoss_1) - type is the class of scenario (e.g. ControlLoss) """ trigger_points = [] ego_vehicles = [] other_actors = [] town = None name = None type = None route = None agent = None weather = carla.WeatherParameters() friction = None subtype = None route_var_name = None ================================================ FILE: scenario_runner/srunner/scenariomanager/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/actor_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a wrapper to access/use user-defined actor controls for example to realize OpenSCENARIO controllers. At the moment only controls implemented in Python are supported. A user must not modify this module. """ import importlib import os import sys import carla from srunner.scenariomanager.actorcontrols.external_control import ExternalControl from srunner.scenariomanager.actorcontrols.npc_vehicle_control import NpcVehicleControl from srunner.scenariomanager.actorcontrols.pedestrian_control import PedestrianControl class ActorControl(object): """ This class provides a wrapper (access mechanism) for user-defined actor controls. The controllers are loaded via importlib. Therefore, the module name of the controller has to match the control class name (e.g. my_own_control.py and MyOwnControl()). At the moment only controllers implemented in Python are supported, or controllers that are completely implemented outside of ScenarioRunner (see ExternalControl). This wrapper is for example used to realize the OpenSCENARIO controllers. Note: If no controllers are provided in OpenSCENARIO a default controller for vehicles and pedestrians is instantiated. For vehicles the NpcVehicleControl is used, for pedestrians it is the PedestrianControl. Args: actor (carla.Actor): Actor that should be controlled by the controller. control_py_module (string): Fully qualified path to the controller python module. args (dict): A dictionary containing all parameters of the controller as (key, value) pairs. Attributes: control_instance: Instance of the user-defined controller. _last_longitudinal_command: Timestamp of the last issued longitudinal control command (e.g. target speed). Defaults to None. Used to avoid that 2 longitudinal control commands are issued at the same time. _last_waypoint_command: Timestamp of the last issued waypoint control command. Defaults to None. Used to avoid that 2 waypoint control commands are issued at the same time. """ control_instance = None _last_longitudinal_command = None _last_waypoint_command = None def __init__(self, actor, control_py_module, args): # use importlib to import the control module if not control_py_module: if isinstance(actor, carla.Walker): self.control_instance = PedestrianControl(actor) elif isinstance(actor, carla.Vehicle): self.control_instance = NpcVehicleControl(actor) else: # use ExternalControl for all misc objects to handle all actors the same way self.control_instance = ExternalControl(actor) else: if ".py" in control_py_module: module_name = os.path.basename(control_py_module).split('.')[0] sys.path.append(os.path.dirname(control_py_module)) module_control = importlib.import_module(module_name) control_class_name = module_control.__name__.title().replace('_', '') else: sys.path.append(os.path.dirname(__file__)) module_control = importlib.import_module(control_py_module) control_class_name = control_py_module.split('.')[-1].title().replace('_', '') self.control_instance = getattr(module_control, control_class_name)(actor, args) def reset(self): """ Reset the controller """ self.control_instance.reset() def update_target_speed(self, target_speed, start_time=None): """ Update the actor's target speed. Args: target_speed (float): New target speed [m/s]. start_time (float): Start time of the new "maneuver" [s]. """ self.control_instance.update_target_speed(target_speed) if start_time: self._last_longitudinal_command = start_time def update_waypoints(self, waypoints, start_time=None): """ Update the actor's waypoints Args: waypoints (List of carla.Transform): List of new waypoints. start_time (float): Start time of the new "maneuver" [s]. """ self.control_instance.update_waypoints(waypoints) if start_time: self._last_waypoint_command = start_time def check_reached_waypoint_goal(self): """ Check if the actor reached the end of the waypoint list returns: True if the end was reached, False otherwise. """ return self.control_instance.check_reached_waypoint_goal() def get_last_longitudinal_command(self): """ Get timestamp of the last issued longitudinal control command (target_speed) returns: Timestamp of last longitudinal control command """ return self._last_longitudinal_command def get_last_waypoint_command(self): """ Get timestamp of the last issued waypoint control command returns: Timestamp of last waypoint control command """ return self._last_waypoint_command def set_init_speed(self): """ Update the actor's initial speed setting """ self.control_instance.set_init_speed() def run_step(self): """ Execute on tick of the controller's control loop """ self.control_instance.run_step() ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/basic_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides the base class for user-defined actor controllers. All user-defined controls must be derived from this class. A user must not modify the module. """ class BasicControl(object): """ This class is the base class for user-defined actor controllers All user-defined agents must be derived from this class. Args: actor (carla.Actor): Actor that should be controlled by the controller. Attributes: _actor (carla.Actor): Controlled actor. Defaults to None. _target_speed (float): Logitudinal target speed of the controller. Defaults to 0. _init_speed (float): Initial longitudinal speed of the controller. Defaults to 0. _waypoints (list of carla.Transform): List of target waypoints the actor should travel along. A waypoint here is of type carla.Transform! Defaults to []. _waypoints_updated (boolean): Defaults to False. _reached_goal (boolean): Defaults to False. """ _actor = None _waypoints = [] _waypoints_updated = False _target_speed = 0 _reached_goal = False _init_speed = False def __init__(self, actor): """ Initialize the actor """ self._actor = actor def update_target_speed(self, speed): """ Update the actor's target speed and set _init_speed to False. Args: speed (float): New target speed [m/s]. """ self._target_speed = speed self._init_speed = False def update_waypoints(self, waypoints, start_time=None): """ Update the actor's waypoints Args: waypoints (List of carla.Transform): List of new waypoints. """ self._waypoints = waypoints self._waypoints_updated = True def set_init_speed(self): """ Set _init_speed to True """ self._init_speed = True def check_reached_waypoint_goal(self): """ Check if the actor reached the end of the waypoint list returns: True if the end was reached, False otherwise. """ return self._reached_goal def reset(self): """ Pure virtual function to reset the controller. This should be implemented in the user-defined agent implementation. """ raise NotImplementedError( "This function must be re-implemented by the user-defined actor control." "If this error becomes visible the class hierarchy is somehow broken") def run_step(self): """ Pure virtual function to run one step of the controllers's control loop. This should be implemented in the user-defined agent implementation. """ raise NotImplementedError( "This function must be re-implemented by the user-defined actor control." "If this error becomes visible the class hierarchy is somehow broken") ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/external_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an example controller for actors, that use an external software for longitudinal and lateral control command calculation. Examples for external controls are: Autoware, CARLA manual_control, etc. This module is not intended for modification. """ from srunner.scenariomanager.actorcontrols.basic_control import BasicControl class ExternalControl(BasicControl): """ Actor control class for actors, with externally implemented longitudinal and lateral controlers (e.g. Autoware). Args: actor (carla.Actor): Actor that should be controlled by the agent. """ def __init__(self, actor, args=None): super(ExternalControl, self).__init__(actor) def reset(self): """ Reset the controller """ if self._actor and self._actor.is_alive: self._actor = None def run_step(self): """ The control loop and setting the actor controls is implemented externally. """ pass ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/npc_vehicle_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an example control for vehicles """ import math import carla from agents.navigation.basic_agent import LocalPlanner from agents.navigation.local_planner import RoadOption from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.actorcontrols.basic_control import BasicControl class NpcVehicleControl(BasicControl): """ Controller class for vehicles derived from BasicControl. The controller makes use of the LocalPlanner implemented in CARLA. Args: actor (carla.Actor): Vehicle actor that should be controlled. """ _args = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05} def __init__(self, actor, args=None): super(NpcVehicleControl, self).__init__(actor) self._local_planner = LocalPlanner( # pylint: disable=undefined-variable self._actor, opt_dict={ 'target_speed': self._target_speed * 3.6, 'lateral_control_dict': self._args}) if self._waypoints: self._update_plan() def _update_plan(self): """ Update the plan (waypoint list) of the LocalPlanner """ plan = [] for transform in self._waypoints: waypoint = CarlaDataProvider.get_map().get_waypoint( transform.location, project_to_road=True, lane_type=carla.LaneType.Any) plan.append((waypoint, RoadOption.LANEFOLLOW)) self._local_planner.set_global_plan(plan) def reset(self): """ Reset the controller """ if self._actor and self._actor.is_alive: if self._local_planner: self._local_planner.reset_vehicle() self._local_planner = None self._actor = None def run_step(self): """ Execute on tick of the controller's control loop If _waypoints are provided, the vehicle moves towards the next waypoint with the given _target_speed, until reaching the final waypoint. Upon reaching the final waypoint, _reached_goal is set to True. If _waypoints is empty, the vehicle moves in its current direction with the given _target_speed. If _init_speed is True, the control command is post-processed to ensure that the initial actor velocity is maintained independent of physics. """ self._reached_goal = False if self._waypoints_updated: self._waypoints_updated = False self._update_plan() target_speed = self._target_speed self._local_planner.set_speed(target_speed * 3.6) control = self._local_planner.run_step(debug=False) # Check if the actor reached the end of the plan if self._local_planner.done(): self._reached_goal = True self._actor.apply_control(control) if self._init_speed: current_speed = math.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2) # If _init_speed is set, and the PID controller is not yet up to the point to take over, # we manually set the vehicle to drive with the correct velocity if abs(target_speed - current_speed) > 3: yaw = self._actor.get_transform().rotation.yaw * (math.pi / 180) vx = math.cos(yaw) * target_speed vy = math.sin(yaw) * target_speed self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0)) ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/pedestrian_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an example control for pedestrians """ import math import carla from srunner.scenariomanager.actorcontrols.basic_control import BasicControl class PedestrianControl(BasicControl): """ Controller class for pedestrians derived from BasicControl. Args: actor (carla.Actor): Pedestrian actor that should be controlled. """ def __init__(self, actor, args=None): if not isinstance(actor, carla.Walker): raise RuntimeError("PedestrianControl: The to be controlled actor is not a pedestrian") super(PedestrianControl, self).__init__(actor) def reset(self): """ Reset the controller """ if self._actor and self._actor.is_alive: self._actor = None def run_step(self): """ Execute on tick of the controller's control loop If _waypoints are provided, the pedestrian moves towards the next waypoint with the given _target_speed, until reaching the final waypoint. Upon reaching the final waypoint, _reached_goal is set to True. If _waypoints is empty, the pedestrians moves in its current direction with the given _target_speed. """ if not self._actor or not self._actor.is_alive: return control = self._actor.get_control() control.speed = self._target_speed if self._waypoints: self._reached_goal = False location = self._waypoints[0].location direction = location - self._actor.get_location() direction_norm = math.sqrt(direction.x**2 + direction.y**2) control.direction = direction / direction_norm self._actor.apply_control(control) if direction_norm < 1.0: self._waypoints = self._waypoints[1:] if not self._waypoints: self._reached_goal = True else: control.direction = self._actor.get_transform().rotation.get_forward_vector() self._actor.apply_control(control) ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an example control for vehicles which does not use CARLA's vehicle engine. Limitations: - Does not respect any traffic regulation: speed limit, traffic light, priorities, etc. - Can only consider obstacles in forward facing reaching (i.e. in tight corners obstacles may be ignored). """ from distutils.util import strtobool import math import cv2 import numpy as np import carla from srunner.scenariomanager.actorcontrols.basic_control import BasicControl from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import GameTime class SimpleVehicleControl(BasicControl): """ Controller class for vehicles derived from BasicControl. The controller directly sets velocities in CARLA, therefore bypassing CARLA's vehicle engine. This allows a very precise speed control, but comes with limitations during cornering. In addition, the controller can consider blocking obstacles, which are classified as dynamic (i.e. vehicles, bikes, pedestrians). Activation of this features is controlled by passing proper arguments to the class constructor. The collision detection uses CARLA's obstacle sensor (sensor.other.obstacle), which checks for obstacles in the direct forward channel of the vehicle, i.e. there are limitation with sideways obstacles and while cornering. Args: actor (carla.Actor): Vehicle actor that should be controlled. args (dictionary): Dictonary of (key, value) arguments to be used by the controller. May include: (consider_obstacles, true/false) - Enable consideration of obstacles (proximity_threshold, distance) - Distance in front of actor in which obstacles are considered (attach_camera, true/false) - Attach OpenCV display to actor (useful for debugging) Attributes: _generated_waypoint_list (list of carla.Transform): List of target waypoints the actor should travel along. A waypoint here is of type carla.Transform! Defaults to []. _last_update (float): Last time step the update function (tick()) was called. Defaults to None. _consider_obstacles (boolean): Enable/Disable consideration of obstacles Defaults to False. _proximity_threshold (float): Distance in front of actor in which obstacles are considered Defaults to infinity. _cv_image (CV Image): Contains the OpenCV image, in case a debug camera is attached to the actor Defaults to None. _camera (sensor.camera.rgb): Debug camera attached to actor Defaults to None. _obstacle_sensor (sensor.other.obstacle): Obstacle sensor attached to actor Defaults to None. _obstacle_distance (float): Distance of the closest obstacle returned by the obstacle sensor Defaults to infinity. _obstacle_actor (carla.Actor): Closest obstacle returned by the obstacle sensor Defaults to None. """ def __init__(self, actor, args=None): super(SimpleVehicleControl, self).__init__(actor) self._generated_waypoint_list = [] self._last_update = None self._consider_obstacles = False self._proximity_threshold = float('inf') self._cv_image = None self._camera = None self._obstacle_sensor = None self._obstacle_distance = float('inf') self._obstacle_actor = None if args and 'consider_obstacles' in args and strtobool(args['consider_obstacles']): self._consider_obstacles = strtobool(args['consider_obstacles']) bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.other.obstacle') bp.set_attribute('distance', '250') if args and 'proximity_threshold' in args: self._proximity_threshold = float(args['proximity_threshold']) bp.set_attribute('distance', str(max(float(args['proximity_threshold']), 250))) bp.set_attribute('hit_radius', '1') bp.set_attribute('only_dynamics', 'True') self._obstacle_sensor = CarlaDataProvider.get_world().spawn_actor( bp, carla.Transform(carla.Location(x=self._actor.bounding_box.extent.x, z=1.0)), attach_to=self._actor) self._obstacle_sensor.listen(lambda event: self._on_obstacle(event)) # pylint: disable=unnecessary-lambda if args and 'attach_camera' in args and strtobool(args['attach_camera']): bp = CarlaDataProvider.get_world().get_blueprint_library().find('sensor.camera.rgb') self._camera = CarlaDataProvider.get_world().spawn_actor(bp, carla.Transform( carla.Location(x=0.0, z=30.0), carla.Rotation(pitch=-60)), attach_to=self._actor) self._camera.listen(lambda image: self._on_camera_update(image)) # pylint: disable=unnecessary-lambda def _on_obstacle(self, event): """ Callback for the obstacle sensor Sets _obstacle_distance and _obstacle_actor according to the closest obstacle found by the sensor. """ if not event: return self._obstacle_distance = event.distance self._obstacle_actor = event.other_actor def _on_camera_update(self, image): """ Callback for the camera sensor Sets the OpenCV image (_cv_image). Requires conversion from BGRA to RGB. """ if not image: return image_data = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) np_image = np.reshape(image_data, (image.height, image.width, 4)) np_image = np_image[:, :, :3] np_image = np_image[:, :, ::-1] self._cv_image = cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB) def reset(self): """ Reset the controller """ if self._camera: self._camera.destroy() self._camera = None if self._obstacle_sensor: self._obstacle_sensor.destroy() self._obstacle_sensor = None if self._actor and self._actor.is_alive: self._actor = None def run_step(self): """ Execute on tick of the controller's control loop If _waypoints are provided, the vehicle moves towards the next waypoint with the given _target_speed, until reaching the final waypoint. Upon reaching the final waypoint, _reached_goal is set to True. If _waypoints is empty, the vehicle moves in its current direction with the given _target_speed. If _consider_obstacles is true, the speed is adapted according to the closest obstacle in front of the actor, if it is within the _proximity_threshold distance. """ if self._cv_image is not None: cv2.imshow("", self._cv_image) cv2.waitKey(1) if self._reached_goal: # Reached the goal, so stop velocity = carla.Vector3D(0, 0, 0) self._actor.set_target_velocity(velocity) return self._reached_goal = False if not self._waypoints: # No waypoints are provided, so we have to create a list of waypoints internally # get next waypoints from map, to avoid leaving the road self._reached_goal = False map_wp = None if not self._generated_waypoint_list: map_wp = CarlaDataProvider.get_map().get_waypoint(CarlaDataProvider.get_location(self._actor)) else: map_wp = CarlaDataProvider.get_map().get_waypoint(self._generated_waypoint_list[-1].location) while len(self._generated_waypoint_list) < 50: map_wps = map_wp.next(3.0) if map_wps: self._generated_waypoint_list.append(map_wps[0].transform) map_wp = map_wps[0] else: break direction_norm = self._set_new_velocity(self._generated_waypoint_list[0].location) if direction_norm < 2.0: self._generated_waypoint_list = self._generated_waypoint_list[1:] else: # When changing from "free" driving without pre-defined waypoints to a defined route with waypoints # it may happen that the first few waypoints are too close to the ego vehicle for obtaining a # reasonable control command. Therefore, we drop these waypoints first. while self._waypoints and self._waypoints[0].location.distance(self._actor.get_location()) < 0.5: self._waypoints = self._waypoints[1:] self._reached_goal = False direction_norm = self._set_new_velocity(self._waypoints[0].location) if direction_norm < 4.0: self._waypoints = self._waypoints[1:] if not self._waypoints: self._reached_goal = True def _set_new_velocity(self, next_location): """ Calculate and set the new actor veloctiy given the current actor location and the _next_location_ If _consider_obstacles is true, the speed is adapted according to the closest obstacle in front of the actor, if it is within the _proximity_threshold distance. Args: next_location (carla.Location): Next target location of the actor returns: direction (carla.Vector3D): Length of direction vector of the actor """ current_time = GameTime.get_time() target_speed = self._target_speed if not self._last_update: self._last_update = current_time if self._consider_obstacles: # If distance is less than the proximity threshold, adapt velocity if self._obstacle_distance < self._proximity_threshold: distance = max(self._obstacle_distance, 0) if distance > 0: current_speed = math.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2) current_speed_other = math.sqrt( self._obstacle_actor.get_velocity().x**2 + self._obstacle_actor.get_velocity().y**2) if current_speed_other < current_speed: acceleration = -0.5 * (current_speed - current_speed_other)**2 / distance target_speed = max(acceleration * (current_time - self._last_update) + current_speed, 0) else: target_speed = 0 # set new linear velocity velocity = carla.Vector3D(0, 0, 0) direction = next_location - CarlaDataProvider.get_location(self._actor) direction_norm = math.sqrt(direction.x**2 + direction.y**2) velocity.x = direction.x / direction_norm * target_speed velocity.y = direction.y / direction_norm * target_speed self._actor.set_target_velocity(velocity) # set new angular velocity current_yaw = CarlaDataProvider.get_transform(self._actor).rotation.yaw # When we have a waypoint list, use the direction between the waypoints to calculate the heading (change) # otherwise use the waypoint heading directly if self._waypoints: delta_yaw = math.degrees(math.atan2(direction.y, direction.x)) - current_yaw else: new_yaw = CarlaDataProvider.get_map().get_waypoint(next_location).transform.rotation.yaw delta_yaw = new_yaw - current_yaw if math.fabs(delta_yaw) > 360: delta_yaw = delta_yaw % 360 if delta_yaw > 180: delta_yaw = delta_yaw - 360 elif delta_yaw < -180: delta_yaw = delta_yaw + 360 angular_velocity = carla.Vector3D(0, 0, 0) if target_speed == 0: angular_velocity.z = 0 else: angular_velocity.z = delta_yaw / (direction_norm / target_speed) self._actor.set_target_angular_velocity(angular_velocity) self._last_update = current_time return direction_norm ================================================ FILE: scenario_runner/srunner/scenariomanager/actorcontrols/vehicle_longitudinal_control.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides an example longitudinal control for vehicles """ import math import carla from srunner.scenariomanager.actorcontrols.basic_control import BasicControl class VehicleLongitudinalControl(BasicControl): """ Controller class for vehicles derived from BasicControl. The controller only controls the throttle of a vehicle, but not the steering. Args: actor (carla.Actor): Vehicle actor that should be controlled. """ def __init__(self, actor, args=None): super(VehicleLongitudinalControl, self).__init__(actor) def reset(self): """ Reset the controller """ if self._actor and self._actor.is_alive: self._actor = None def run_step(self): """ Execute on tick of the controller's control loop The control loop is very simplistic: If the actor speed is below the _target_speed, set throttle to 1.0, otherwise, set throttle to 0.0 Note, that this is a longitudinal controller only. If _init_speed is True, the control command is post-processed to ensure that the initial actor velocity is maintained independent of physics. """ control = self._actor.get_control() velocity = self._actor.get_velocity() current_speed = math.sqrt(velocity.x**2 + velocity.y**2) if current_speed < self._target_speed: control.throttle = 1.0 else: control.throttle = 0.0 self._actor.apply_control(control) if self._init_speed: if abs(self._target_speed - current_speed) > 3: yaw = self._actor.get_transform().rotation.yaw * (math.pi / 180) vx = math.cos(yaw) * self._target_speed vy = math.sin(yaw) * self._target_speed self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0)) ================================================ FILE: scenario_runner/srunner/scenariomanager/carla_data_provider.py ================================================ #!/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 import numpy.random as 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 = dict() _actor_location_map = dict() _actor_transform_map = dict() _traffic_light_map = dict() _carla_actor_pool = dict() _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 _ego_vehicle = None _rng = random.RandomState(2000) _time_step = -1 @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 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_ego(vehicle): """ Set the ego vehicle """ CarlaDataProvider._ego_vehicle = vehicle @staticmethod def get_ego(): """ Get the CARLA ego """ return CarlaDataProvider._ego_vehicle @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 set_weather(weather): """ Set the weather of the world """ CarlaDataProvider._world.set_weather(weather) @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 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])|$)') name = lambda x: ' '.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 CarlaDataProvider._traffic_light_map.keys(): 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) if waypoint is not None and len(waypoint) > 0: waypoint = waypoint[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 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"): """ 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: blueprint = CarlaDataProvider._rng.choice(CarlaDataProvider._blueprint_library.filter(model)) 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): """ Forward a CARLA command batch to spawn actors to CARLA, and gather the responses. Returns list of actors on success, none otherwise """ actors = [] sync_mode = CarlaDataProvider.is_sync_mode() if CarlaDataProvider._client and batch is not None: responses = CarlaDataProvider._client.apply_batch_sync(batch, sync_mode) else: return None # wait for the actors to be spawned properly before we do anything if sync_mode: CarlaDataProvider._world.tick() else: CarlaDataProvider._world.wait_for_tick() actor_ids = [] if responses: for response in responses: if not response.error: actor_ids.append(response.actor_id) carla_actors = CarlaDataProvider._world.get_actors(actor_ids) for actor in carla_actors: actors.append(actor) return actors @staticmethod def request_new_actor(model, spawn_point, rolename='scenario', autopilot=False, random_location=False, color=None, actor_category="car"): """ This method tries to create a new actor, returning it if successful (None otherwise). """ blueprint = CarlaDataProvider.create_blueprint(model, rolename, color, actor_category) 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: raise RuntimeError( "Error: Unable to spawn vehicle {} at {}".format(blueprint.id, spawn_point)) else: # Let's deactivate the autopilot of the actor if it belongs to vehicle if actor in CarlaDataProvider._blueprint_library.filter('vehicle.*'): actor.set_autopilot(autopilot) else: pass # wait for the actor to be spawned properly before we do anything if CarlaDataProvider.is_sync_mode(): CarlaDataProvider._world.tick() else: CarlaDataProvider._world.wait_for_tick() if actor is None: return None CarlaDataProvider._carla_actor_pool[actor.id] = actor CarlaDataProvider.register_actor(actor) return actor @staticmethod def request_new_actors(actor_list): """ 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 batch = [] actors = [] CarlaDataProvider.generate_spawn_points() for actor in actor_list: # Get the blueprint blueprint = CarlaDataProvider.create_blueprint(actor.model, actor.rolename, actor.color, actor.category) # 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] 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 _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.category == 'misc': command.then(PhysicsCommand(FutureActor, True)) elif 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)) batch.append(command) actors = CarlaDataProvider.handle_actor_batch(batch) if not actors: return None 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'): """ 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) 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] 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) if actors is None: return None 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 set_time_step(time_step): CarlaDataProvider._time_step = time_step @staticmethod def get_time_step(): """ Set the time-step for debug. """ return CarlaDataProvider._time_step @staticmethod def cleanup(): """ Obtain the time-step for debug. """ 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] if actor.is_alive: 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 = dict() CarlaDataProvider._client = None CarlaDataProvider._spawn_points = None CarlaDataProvider._spawn_index = 0 CarlaDataProvider._ego_vehicle = None CarlaDataProvider._rng = random.RandomState(2000) ================================================ FILE: scenario_runner/srunner/scenariomanager/result_writer.py ================================================ #!/usr/bin/env python # Copyright (c) 2018-2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module contains the result gatherer and write for CARLA scenarios. It shall be used from the ScenarioManager only. """ from __future__ import print_function import time from tabulate import tabulate class ResultOutputProvider(object): """ This module contains the _result gatherer and write for CARLA scenarios. It shall be used from the ScenarioManager only. """ def __init__(self, data, result, stdout=True, filename=None, junit=None): """ Setup all parameters - _data contains all scenario-related information - _result is overall pass/fail info - _stdout (True/False) is used to (de)activate terminal output - _filename is used to (de)activate file output in tabular form - _junit is used to (de)activate file output in _junit form """ self._data = data self._result = result self._stdout = stdout self._filename = filename self._junit = junit self._start_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.start_system_time)) self._end_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime(self._data.end_system_time)) def write(self): """ Public write function """ if self._junit is not None: self._write_to_junit() output = self.create_output_text() if self._filename is not None: with open(self._filename, 'w') as fd: fd.write(output) if self._stdout: print(output) def create_output_text(self): """ Creates the output message """ output = "\n" output += " ======= Results of Scenario: {} ---- {} =======\n".format( self._data.scenario_tree.name, self._result) end_line_length = len(output) - 3 output += "\n" # Lis of all the actors output += " > Ego vehicles:\n" for ego_vehicle in self._data.ego_vehicles: output += "{}; ".format(ego_vehicle) output += "\n\n" output += " > Other actors:\n" for actor in self._data.other_actors: output += "{}; ".format(actor) output += "\n\n" # Simulation part output += " > Simulation Information\n" system_time = round(self._data.scenario_duration_system, 2) game_time = round(self._data.scenario_duration_game, 2) ratio = round(self._data.scenario_duration_game / self._data.scenario_duration_system, 3) list_statistics = [["Start Time", "{}".format(self._start_time)]] list_statistics.extend([["End Time", "{}".format(self._end_time)]]) list_statistics.extend([["Duration (System Time)", "{}s".format(system_time)]]) list_statistics.extend([["Duration (Game Time)", "{}s".format(game_time)]]) list_statistics.extend([["Ratio (System Time / Game Time)", "{}s".format(ratio)]]) output += tabulate(list_statistics, tablefmt='fancy_grid') output += "\n\n" # Criteria part output += " > Criteria Information\n" header = ['Actor', 'Criterion', 'Result', 'Actual Value', 'Expected Value'] list_statistics = [header] for criterion in self._data.scenario.get_criteria(): name_string = criterion.name if criterion.optional: name_string += " (Opt.)" else: name_string += " (Req.)" actor = "{} (id={})".format(criterion.actor.type_id[8:], criterion.actor.id) criteria = name_string result = "FAILURE" if criterion.test_status == "RUNNING" else criterion.test_status actual_value = criterion.actual_value expected_value = criterion.expected_value_success list_statistics.extend([[actor, criteria, result, actual_value, expected_value]]) # Timeout actor = "" criteria = "Timeout (Req.)" result = "SUCCESS" if self._data.scenario_duration_game < self._data.scenario.timeout else "FAILURE" actual_value = round(self._data.scenario_duration_game, 2) expected_value = round(self._data.scenario.timeout, 2) list_statistics.extend([[actor, criteria, result, actual_value, expected_value]]) # Global and final output message list_statistics.extend([['', 'GLOBAL RESULT', self._result, '', '']]) output += tabulate(list_statistics, tablefmt='fancy_grid') output += "\n" output += " " + "=" * end_line_length + "\n" return output def _write_to_junit(self): """ Writing to Junit XML """ test_count = 0 failure_count = 0 for criterion in self._data.scenario.get_criteria(): test_count += 1 if criterion.test_status != "SUCCESS": failure_count += 1 # handle timeout test_count += 1 if self._data.scenario_duration_game >= self._data.scenario.timeout: failure_count += 1 junit_file = open(self._junit, "w") junit_file.write("\n") test_suites_string = ("\n" % (test_count, failure_count, self._start_time, self._data.scenario_duration_system)) junit_file.write(test_suites_string) test_suite_string = (" \n" % (self._data.scenario_tree.name, test_count, failure_count, self._data.scenario_duration_system)) junit_file.write(test_suite_string) for criterion in self._data.scenario.get_criteria(): testcase_name = criterion.name + "_" + \ criterion.actor.type_id[8:] + "_" + str(criterion.actor.id) result_string = (" \n".format( testcase_name, self._data.scenario_tree.name)) if criterion.test_status != "SUCCESS": result_string += " \n".format( criterion.name, criterion.actual_value) else: result_string += " Exact Value: {} = {}\n".format( criterion.name, criterion.actual_value) result_string += " \n" junit_file.write(result_string) # Handle timeout separately result_string = (" \n".format( self._data.scenario_duration_system, self._data.scenario_tree.name)) if self._data.scenario_duration_game >= self._data.scenario.timeout: result_string += " \n".format( "Duration", self._data.scenario_duration_game) else: result_string += " Exact Value: {} = {}\n".format( "Duration", self._data.scenario_duration_game) result_string += " \n" junit_file.write(result_string) junit_file.write(" \n") junit_file.write("\n") junit_file.close() ================================================ FILE: scenario_runner/srunner/scenariomanager/scenario_manager.py ================================================ #!/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 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 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._running = False self._timestamp_last_run = 0.0 self._timeout = timeout self._watchdog = Watchdog(float(self._timeout)) self.scenario_duration_system = 0.0 self.scenario_duration_game = 0.0 self.start_system_time = None self.end_system_time = 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.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): """ 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) 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.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._watchdog.stop() 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() # 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._agent is not None: self.ego_vehicles[0].apply_control(ego_action) 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): """ 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) output.write() return failure or timeout ================================================ FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py ================================================ #!/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 atomic scenario behaviors required to realize complex, realistic scenarios such as "follow a leading vehicle", "lane change", etc. The atomic behaviors are implemented with py_trees. """ from __future__ import print_function import copy import math import operator import os import random import time import subprocess import numpy as np import py_trees from py_trees.blackboard import Blackboard import carla from agents.navigation.basic_agent import BasicAgent, LocalPlanner from agents.navigation.local_planner import RoadOption from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.actorcontrols.actor_control import ActorControl from srunner.scenariomanager.timer import GameTime from srunner.tools.scenario_helper import detect_lane_obstacle from srunner.tools.scenario_helper import generate_target_waypoint_list_multilane import srunner.tools EPSILON = 0.001 def calculate_distance(location, other_location, global_planner=None): """ Method to calculate the distance between to locations Note: It uses the direct distance between the current location and the target location to estimate the time to arrival. To be accurate, it would have to use the distance along the (shortest) route between the two locations. """ if global_planner: distance = 0 # Get the route route = global_planner.trace_route(location, other_location) # Get the distance of the route for i in range(1, len(route)): curr_loc = route[i][0].transform.location prev_loc = route[i - 1][0].transform.location distance += curr_loc.distance(prev_loc) return distance return location.distance(other_location) def get_actor_control(actor): """ Method to return the type of control to the actor. """ control = actor.get_control() actor_type = actor.type_id.split('.')[0] if not isinstance(actor, carla.Walker): control.steering = 0 else: control.speed = 0 return control, actor_type class AtomicBehavior(py_trees.behaviour.Behaviour): """ Base class for all atomic behaviors used to setup a scenario *All behaviors should use this class as parent* Important parameters: - name: Name of the atomic behavior """ def __init__(self, name, actor=None): """ Default init. Has to be called via super from derived class """ super(AtomicBehavior, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self.name = name self._actor = actor def setup(self, unused_timeout=15): """ Default setup """ self.logger.debug("%s.setup()" % (self.__class__.__name__)) return True def initialise(self): """ Initialise setup terminates WaypointFollowers Check whether WF for this actor is running and terminate all active WFs """ if self._actor is not None: try: check_attr = operator.attrgetter("running_WF_actor_{}".format(self._actor.id)) terminate_wf = copy.copy(check_attr(py_trees.blackboard.Blackboard())) py_trees.blackboard.Blackboard().set( "terminate_WF_actor_{}".format(self._actor.id), terminate_wf, overwrite=True) except AttributeError: # It is ok to continue, if the Blackboard variable does not exist pass self.logger.debug("%s.initialise()" % (self.__class__.__name__)) def terminate(self, new_status): """ Default terminate. Can be extended in derived class """ self.logger.debug("%s.terminate()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) class RunScript(AtomicBehavior): """ This is an atomic behavior to start execution of an additional script. Args: script (str): String containing the interpreter, scriptpath and arguments Example: "python /path/to/script.py --arg1" base_path (str): String containing the base path of for the script Attributes: _script (str): String containing the interpreter, scriptpath and arguments Example: "python /path/to/script.py --arg1" _base_path (str): String containing the base path of for the script Example: "/path/to/" Note: This is intended for the use with OpenSCENARIO. Be aware of security side effects. """ def __init__(self, script, base_path=None, name="RunScript"): """ Setup parameters """ super(RunScript, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._script = script self._base_path = base_path def update(self): """ Start script """ path = None script_components = self._script.split(' ') if len(script_components) > 1: path = script_components[1] if not os.path.isfile(path): path = os.path.join(self._base_path, path) if not os.path.isfile(path): new_status = py_trees.common.Status.FAILURE print("Script file does not exists {}".format(path)) else: subprocess.Popen(self._script, shell=True, cwd=self._base_path) new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class ChangeWeather(AtomicBehavior): """ Atomic to write a new weather configuration into the blackboard. Used in combination with WeatherBehavior() to have a continuous weather simulation. The behavior immediately terminates with SUCCESS after updating the blackboard. Args: weather (srunner.scenariomanager.weather_sim.Weather): New weather settings. name (string): Name of the behavior. Defaults to 'UpdateWeather'. Attributes: _weather (srunner.scenariomanager.weather_sim.Weather): Weather settings. """ def __init__(self, weather, name="ChangeWeather"): """ Setup parameters """ super(ChangeWeather, self).__init__(name) self._weather = weather def update(self): """ Write weather into blackboard and exit with success returns: py_trees.common.Status.SUCCESS """ py_trees.blackboard.Blackboard().set("CarlaWeather", self._weather, overwrite=True) return py_trees.common.Status.SUCCESS class ChangeRoadFriction(AtomicBehavior): """ Atomic to update the road friction in CARLA. The behavior immediately terminates with SUCCESS after updating the friction. Args: friction (float): New friction coefficient. name (string): Name of the behavior. Defaults to 'UpdateRoadFriction'. Attributes: _friction (float): Friction coefficient. """ def __init__(self, friction, name="ChangeRoadFriction"): """ Setup parameters """ super(ChangeRoadFriction, self).__init__(name) self._friction = friction def update(self): """ Update road friction. Spawns new friction blueprint and removes the old one, if existing. returns: py_trees.common.Status.SUCCESS """ for actor in CarlaDataProvider.get_world().get_actors().filter('static.trigger.friction'): actor.destroy() friction_bp = CarlaDataProvider.get_world().get_blueprint_library().find('static.trigger.friction') extent = carla.Location(1000000.0, 1000000.0, 1000000.0) friction_bp.set_attribute('friction', str(self._friction)) friction_bp.set_attribute('extent_x', str(extent.x)) friction_bp.set_attribute('extent_y', str(extent.y)) friction_bp.set_attribute('extent_z', str(extent.z)) # Spawn Trigger Friction transform = carla.Transform() transform.location = carla.Location(-10000.0, -10000.0, 0.0) CarlaDataProvider.get_world().spawn_actor(friction_bp, transform) return py_trees.common.Status.SUCCESS class ChangeActorControl(AtomicBehavior): """ Atomic to change the longitudinal/lateral control logic for an actor. The (actor, controller) pair is stored inside the Blackboard. The behavior immediately terminates with SUCCESS after the controller. Args: actor (carla.Actor): Actor that should be controlled by the controller. control_py_module (string): Name of the python module containing the implementation of the controller. args (dictionary): Additional arguments for the controller. name (string): Name of the behavior. Defaults to 'ChangeActorControl'. Attributes: _actor_control (ActorControl): Instance of the actor control. """ def __init__(self, actor, control_py_module, args, name="ChangeActorControl"): """ Setup actor controller. """ super(ChangeActorControl, self).__init__(name, actor) self._actor_control = ActorControl(actor, control_py_module=control_py_module, args=args) def update(self): """ Write (actor, controler) pair to Blackboard, or update the controller if actor already exists as a key. returns: py_trees.common.Status.SUCCESS """ actor_dict = {} try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if actor_dict: if self._actor.id in actor_dict: actor_dict[self._actor.id].reset() actor_dict[self._actor.id] = self._actor_control py_trees.blackboard.Blackboard().set("ActorsWithController", actor_dict, overwrite=True) return py_trees.common.Status.SUCCESS class UpdateAllActorControls(AtomicBehavior): """ Atomic to update (run one control loop step) all actor controls. The behavior is always in RUNNING state. Args: name (string): Name of the behavior. Defaults to 'UpdateAllActorControls'. """ def __init__(self, name="UpdateAllActorControls"): """ Constructor """ super(UpdateAllActorControls, self).__init__(name) def update(self): """ Execute one control loop step for all actor controls. returns: py_trees.common.Status.RUNNING """ actor_dict = {} try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass for actor_id in actor_dict: actor_dict[actor_id].run_step() return py_trees.common.Status.RUNNING class ChangeActorTargetSpeed(AtomicBehavior): """ Atomic to change the target speed for an actor controller. The behavior is in RUNNING state until the distance/duration conditions are satisfied, or if a second ChangeActorTargetSpeed atomic for the same actor is triggered. Args: actor (carla.Actor): Controlled actor. target_speed (float): New target speed [m/s]. init_speed (boolean): Flag to indicate if the speed is the initial actor speed. Defaults to False. duration (float): Duration of the maneuver [s]. Defaults to None. distance (float): Distance of the maneuver [m]. Defaults to None. relative_actor (carla.Actor): If the target speed setting should be relative to another actor. Defaults to None. value (float): Offset, if the target speed setting should be relative to another actor. Defaults to None. value_type (string): Either 'Delta' or 'Factor' influencing how the offset to the reference actors velocity is applied. Defaults to None. continuous (boolean): If True, the atomic remains in RUNNING, independent of duration or distance. Defaults to False. name (string): Name of the behavior. Defaults to 'ChangeActorTargetSpeed'. Attributes: _target_speed (float): New target speed [m/s]. _init_speed (boolean): Flag to indicate if the speed is the initial actor speed. Defaults to False. _start_time (float): Start time of the atomic [s]. Defaults to None. _start_location (carla.Location): Start location of the atomic. Defaults to None. _duration (float): Duration of the maneuver [s]. Defaults to None. _distance (float): Distance of the maneuver [m]. Defaults to None. _relative_actor (carla.Actor): If the target speed setting should be relative to another actor. Defaults to None. _value (float): Offset, if the target speed setting should be relative to another actor. Defaults to None. _value_type (string): Either 'Delta' or 'Factor' influencing how the offset to the reference actors velocity is applied. Defaults to None. _continuous (boolean): If True, the atomic remains in RUNNING, independent of duration or distance. Defaults to False. """ def __init__(self, actor, target_speed, init_speed=False, duration=None, distance=None, relative_actor=None, value=None, value_type=None, continuous=False, name="ChangeActorTargetSpeed"): """ Setup parameters """ super(ChangeActorTargetSpeed, self).__init__(name, actor) self._target_speed = target_speed self._init_speed = init_speed self._start_time = None self._start_location = None self._relative_actor = relative_actor self._value = value self._value_type = value_type self._continuous = continuous self._duration = duration self._distance = distance def initialise(self): """ Set initial parameters such as _start_time and _start_location, and get (actor, controller) pair from Blackboard. May throw if actor is not available as key for the ActorsWithController dictionary from Blackboard. """ actor_dict = {} try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if not actor_dict or not self._actor.id in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() self._start_location = CarlaDataProvider.get_location(self._actor) if self._relative_actor: relative_velocity = CarlaDataProvider.get_velocity(self._relative_actor) # get target velocity if self._value_type == 'delta': self._target_speed = relative_velocity + self._value elif self._value_type == 'factor': self._target_speed = relative_velocity * self._value else: print('self._value_type must be delta or factor') actor_dict[self._actor.id].update_target_speed(self._target_speed, start_time=self._start_time) if self._init_speed: actor_dict[self._actor.id].set_init_speed() super(ChangeActorTargetSpeed, self).initialise() def update(self): """ Check the actor's current state and update target speed, if it is relative to another actor. returns: py_trees.common.Status.SUCCESS, if the duration or distance driven exceeded limits if another ChangeActorTargetSpeed atomic for the same actor was triggered. py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary. py_trees.common.Status.FAILURE, else. """ try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if not actor_dict or not self._actor.id in actor_dict: return py_trees.common.Status.FAILURE if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time: return py_trees.common.Status.SUCCESS new_status = py_trees.common.Status.RUNNING if self._relative_actor: relative_velocity = CarlaDataProvider.get_velocity(self._relative_actor) # get target velocity if self._value_type == 'delta': actor_dict[self._actor.id].update_target_speed(relative_velocity + self._value) elif self._value_type == 'factor': actor_dict[self._actor.id].update_target_speed(relative_velocity * self._value) else: print('self._value_type must be delta or factor') # check duration and driven_distance if not self._continuous: if (self._duration is not None) and (GameTime.get_time() - self._start_time > self._duration): new_status = py_trees.common.Status.SUCCESS driven_distance = CarlaDataProvider.get_location(self._actor).distance(self._start_location) if (self._distance is not None) and (driven_distance > self._distance): new_status = py_trees.common.Status.SUCCESS if self._distance is None and self._duration is None: new_status = py_trees.common.Status.SUCCESS return new_status class ChangeActorWaypoints(AtomicBehavior): """ Atomic to change the waypoints for an actor controller. The behavior is in RUNNING state until the last waypoint is reached, or if a second waypoint related atomic for the same actor is triggered. These are: - ChangeActorWaypoints - ChangeActorWaypointsToReachPosition - ChangeActorLateralMotion Args: actor (carla.Actor): Controlled actor. waypoints (List of carla.Transform): List of waypoints (CARLA transforms). name (string): Name of the behavior. Defaults to 'ChangeActorWaypoints'. Attributes: _waypoints (List of carla.Transform): List of waypoints (CARLA transforms). _start_time (float): Start time of the atomic [s]. Defaults to None. """ def __init__(self, actor, waypoints, name="ChangeActorWaypoints"): """ Setup parameters """ super(ChangeActorWaypoints, self).__init__(name, actor) self._waypoints = waypoints self._start_time = None def initialise(self): """ Set _start_time and get (actor, controller) pair from Blackboard. Set waypoint list for actor controller. May throw if actor is not available as key for the ActorsWithController dictionary from Blackboard. """ actor_dict = {} try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if not actor_dict or not self._actor.id in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() actor_dict[self._actor.id].update_waypoints(self._waypoints, start_time=self._start_time) super(ChangeActorWaypoints, self).initialise() def update(self): """ Check the actor's state along the waypoint route. returns: py_trees.common.Status.SUCCESS, if the final waypoint was reached, or if another ChangeActorWaypoints atomic for the same actor was triggered. py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary. py_trees.common.Status.FAILURE, else. """ try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if not actor_dict or not self._actor.id in actor_dict: return py_trees.common.Status.FAILURE if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time: return py_trees.common.Status.SUCCESS new_status = py_trees.common.Status.RUNNING if actor_dict[self._actor.id].check_reached_waypoint_goal(): new_status = py_trees.common.Status.SUCCESS return new_status class ChangeActorWaypointsToReachPosition(ChangeActorWaypoints): """ Atomic to change the waypoints for an actor controller in order to reach a given position. The behavior is in RUNNING state until the last waypoint is reached, or if a second waypoint related atomic for the same actor is triggered. These are: - ChangeActorWaypoints - ChangeActorWaypointsToReachPosition - ChangeActorLateralMotion Args: actor (carla.Actor): Controlled actor. position (carla.Transform): CARLA transform to be reached by the actor. name (string): Name of the behavior. Defaults to 'ChangeActorWaypointsToReachPosition'. Attributes: _waypoints (List of carla.Transform): List of waypoints (CARLA transforms). _end_transform (carla.Transform): Final position (CARLA transform). _start_time (float): Start time of the atomic [s]. Defaults to None. _grp (GlobalPlanner): global planner instance of the town """ def __init__(self, actor, position, name="ChangeActorWaypointsToReachPosition"): """ Setup parameters """ super(ChangeActorWaypointsToReachPosition, self).__init__(actor, []) self._end_transform = position town_map = CarlaDataProvider.get_map() dao = GlobalRoutePlannerDAO(town_map, 2) self._grp = GlobalRoutePlanner(dao) self._grp.setup() def initialise(self): """ Set _start_time and get (actor, controller) pair from Blackboard. Generate a waypoint list (route) which representes the route. Set this waypoint list for the actor controller. May throw if actor is not available as key for the ActorsWithController dictionary from Blackboard. """ # get start position position_actor = CarlaDataProvider.get_location(self._actor) # calculate plan with global_route_planner function plan = self._grp.trace_route(position_actor, self._end_transform.location) for elem in plan: self._waypoints.append(elem[0].transform) super(ChangeActorWaypointsToReachPosition, self).initialise() class ChangeActorLateralMotion(AtomicBehavior): """ Atomic to change the waypoints for an actor controller. The behavior is in RUNNING state until the last waypoint is reached, or if a second waypoint related atomic for the same actor is triggered. These are: - ChangeActorWaypoints - ChangeActorWaypointsToReachPosition - ChangeActorLateralMotion Args: actor (carla.Actor): Controlled actor. direction (string): Lane change direction ('left' or 'right'). Defaults to 'left'. distance_lane_change (float): Distance of the lance change [meters]. Defaults to 25. distance_other_lane (float): Driven distance after the lange change [meters]. Defaults to 100. name (string): Name of the behavior. Defaults to 'ChangeActorLateralMotion'. Attributes: _waypoints (List of carla.Transform): List of waypoints representing the lane change (CARLA transforms). _direction (string): Lane change direction ('left' or 'right'). _distance_same_lane (float): Distance on the same lane before the lane change starts [meters] Constant to 5. _distance_other_lane (float): Max. distance on the target lane after the lance change [meters] Constant to 100. _distance_lane_change (float): Max. total distance of the lane change [meters]. _pos_before_lane_change: carla.Location of the actor before the lane change. Defaults to None. _target_lane_id (int): Id of the target lane Defaults to None. _start_time (float): Start time of the atomic [s]. Defaults to None. """ def __init__(self, actor, direction='left', distance_lane_change=25, distance_other_lane=100, name="ChangeActorLateralMotion"): """ Setup parameters """ super(ChangeActorLateralMotion, self).__init__(name, actor) self._waypoints = [] self._direction = direction self._distance_same_lane = 5 self._distance_other_lane = distance_other_lane self._distance_lane_change = distance_lane_change self._pos_before_lane_change = None self._target_lane_id = None self._start_time = None def initialise(self): """ Set _start_time and get (actor, controller) pair from Blackboard. Generate a waypoint list (route) which representes the lane change. Set this waypoint list for the actor controller. May throw if actor is not available as key for the ActorsWithController dictionary from Blackboard. """ actor_dict = {} try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if not actor_dict or not self._actor.id in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() # get start position position_actor = CarlaDataProvider.get_map().get_waypoint(CarlaDataProvider.get_location(self._actor)) # calculate plan with scenario_helper function plan, self._target_lane_id = generate_target_waypoint_list_multilane( position_actor, self._direction, self._distance_same_lane, self._distance_other_lane, self._distance_lane_change, check='false') for elem in plan: self._waypoints.append(elem[0].transform) actor_dict[self._actor.id].update_waypoints(self._waypoints, start_time=self._start_time) super(ChangeActorLateralMotion, self).initialise() def update(self): """ Check the actor's current state and if the lane change was completed returns: py_trees.common.Status.SUCCESS, if lane change was successful, or if another ChangeActorLateralMotion atomic for the same actor was triggered. py_trees.common.Status.FAILURE, if the actor is not found in ActorsWithController Blackboard dictionary. py_trees.common.Status.FAILURE, else. """ try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass if not actor_dict or not self._actor.id in actor_dict: return py_trees.common.Status.FAILURE if actor_dict[self._actor.id].get_last_waypoint_command() != self._start_time: return py_trees.common.Status.SUCCESS new_status = py_trees.common.Status.RUNNING current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location()) current_lane_id = current_position_actor.lane_id if current_lane_id == self._target_lane_id: # driving on new lane distance = current_position_actor.transform.location.distance(self._pos_before_lane_change) if distance > self._distance_other_lane: # long enough distance on new lane --> SUCCESS new_status = py_trees.common.Status.SUCCESS else: # no lane change yet self._pos_before_lane_change = current_position_actor.transform.location return new_status class ActorTransformSetterToOSCPosition(AtomicBehavior): """ OpenSCENARIO atomic This class contains an atomic behavior to set the transform of an OpenSCENARIO actor. Important parameters: - actor: CARLA actor to execute the behavior - osc_position: OpenSCENARIO position - physics [optional]: If physics is true, the actor physics will be reactivated upon success The behavior terminates when actor is set to the new actor transform (closer than 1 meter) NOTE: It is very important to ensure that the actor location is spawned to the new transform because of the appearence of a rare runtime processing error. WaypointFollower with LocalPlanner, might fail if new_status is set to success before the actor is really positioned at the new transform. Therefore: calculate_distance(actor, transform) < 1 meter """ def __init__(self, actor, osc_position, physics=True, name="ActorTransformSetterToOSCPosition"): """ Setup parameters """ super(ActorTransformSetterToOSCPosition, self).__init__(name, actor) self._osc_position = osc_position self._physics = physics self._osc_transform = None def initialise(self): super(ActorTransformSetterToOSCPosition, self).initialise() if self._actor.is_alive: self._actor.set_target_velocity(carla.Vector3D(0, 0, 0)) self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) def update(self): """ Transform actor """ new_status = py_trees.common.Status.RUNNING # calculate transform with method in openscenario_parser.py self._osc_transform = srunner.tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform( self._osc_position) self._actor.set_transform(self._osc_transform) if not self._actor.is_alive: new_status = py_trees.common.Status.FAILURE if calculate_distance(self._actor.get_location(), self._osc_transform.location) < 1.0: if self._physics: self._actor.set_simulate_physics(enabled=True) new_status = py_trees.common.Status.SUCCESS return new_status class AccelerateToVelocity(AtomicBehavior): """ This class contains an atomic acceleration behavior. The controlled traffic participant will accelerate with _throttle_value_ until reaching a given _target_velocity_ Important parameters: - actor: CARLA actor to execute the behavior - throttle_value: The amount of throttle used to accelerate in [0,1] - target_velocity: The target velocity the actor should reach in m/s The behavior will terminate, if the actor's velocity is at least target_velocity """ def __init__(self, actor, throttle_value, target_velocity, name="Acceleration"): """ Setup parameters including acceleration value (via throttle_value) and target velocity """ super(AccelerateToVelocity, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) self._throttle_value = throttle_value self._target_velocity = target_velocity def initialise(self): # In case of walkers, we have to extract the current heading if self._type == 'walker': self._control.speed = self._target_velocity self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector() super(AccelerateToVelocity, self).initialise() def update(self): """ Set throttle to throttle_value, as long as velocity is < target_velocity """ new_status = py_trees.common.Status.RUNNING if self._type == 'vehicle': if CarlaDataProvider.get_velocity(self._actor) < self._target_velocity: self._control.throttle = self._throttle_value else: new_status = py_trees.common.Status.SUCCESS self._control.throttle = 0 self._actor.apply_control(self._control) self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class AccelerateToCatchUp(AtomicBehavior): """ This class contains an atomic acceleration behavior. The car will accelerate until it is faster than another car, in order to catch up distance. This behaviour is especially useful before a lane change (e.g. LaneChange atom). Important parameters: - actor: CARLA actor to execute the behaviour - other_actor: Reference CARLA actor, actor you want to catch up to - throttle_value: acceleration value between 0.0 and 1.0 - delta_velocity: speed up to the velocity of other actor plus delta_velocity - trigger_distance: distance between the actors - max_distance: driven distance to catch up has to be smaller than max_distance The behaviour will terminate succesful, when the two actors are in trigger_distance. If max_distance is driven by the actor before actors are in trigger_distance, then the behaviour ends with a failure. """ def __init__(self, actor, other_actor, throttle_value=1, delta_velocity=10, trigger_distance=5, max_distance=500, name="AccelerateToCatchUp"): """ Setup parameters The target_speet is calculated on the fly. """ super(AccelerateToCatchUp, self).__init__(name, actor) self._other_actor = other_actor self._throttle_value = throttle_value self._delta_velocity = delta_velocity # 1m/s=3.6km/h self._trigger_distance = trigger_distance self._max_distance = max_distance self._control, self._type = get_actor_control(actor) self._initial_actor_pos = None def initialise(self): # get initial actor position self._initial_actor_pos = CarlaDataProvider.get_location(self._actor) super(AccelerateToCatchUp, self).initialise() def update(self): # get actor speed actor_speed = CarlaDataProvider.get_velocity(self._actor) target_speed = CarlaDataProvider.get_velocity(self._other_actor) + self._delta_velocity # distance between actors distance = CarlaDataProvider.get_location(self._actor).distance( CarlaDataProvider.get_location(self._other_actor)) # driven distance of actor driven_distance = CarlaDataProvider.get_location(self._actor).distance(self._initial_actor_pos) if actor_speed < target_speed: # set throttle to throttle_value to accelerate self._control.throttle = self._throttle_value if actor_speed >= target_speed: # keep velocity until the actors are in trigger distance self._control.throttle = 0 self._actor.apply_control(self._control) # new status: if distance <= self._trigger_distance: new_status = py_trees.common.Status.SUCCESS elif driven_distance > self._max_distance: new_status = py_trees.common.Status.FAILURE else: new_status = py_trees.common.Status.RUNNING return new_status class KeepVelocity(AtomicBehavior): """ This class contains an atomic behavior to keep the provided velocity. The controlled traffic participant will accelerate as fast as possible until reaching a given _target_velocity_, which is then maintained for as long as this behavior is active. Important parameters: - actor: CARLA actor to execute the behavior - target_velocity: The target velocity the actor should reach - duration[optional]: Duration in seconds of this behavior - distance[optional]: Maximum distance in meters covered by the actor during this behavior A termination can be enforced by providing distance or duration values. Alternatively, a parallel termination behavior has to be used. """ def __init__(self, actor, target_velocity, duration=float("inf"), distance=float("inf"), name="KeepVelocity"): """ Setup parameters including acceleration value (via throttle_value) and target velocity """ super(KeepVelocity, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._target_velocity = target_velocity self._control, self._type = get_actor_control(actor) self._map = self._actor.get_world().get_map() self._waypoint = self._map.get_waypoint(self._actor.get_location()) self._duration = duration self._target_distance = distance self._distance = 0 self._start_time = 0 self._location = None def initialise(self): self._location = CarlaDataProvider.get_location(self._actor) self._start_time = GameTime.get_time() # In case of walkers, we have to extract the current heading if self._type == 'walker': self._control.speed = self._target_velocity self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector() super(KeepVelocity, self).initialise() def update(self): """ As long as the stop condition (duration or distance) is not violated, set a new vehicle control For vehicles: set throttle to throttle_value, as long as velocity is < target_velocity For walkers: simply apply the given self._control """ new_status = py_trees.common.Status.RUNNING if self._type == 'vehicle': if CarlaDataProvider.get_velocity(self._actor) < self._target_velocity: self._control.throttle = 1.0 else: self._control.throttle = 0.0 self._actor.apply_control(self._control) new_location = CarlaDataProvider.get_location(self._actor) self._distance += calculate_distance(self._location, new_location) self._location = new_location if self._distance > self._target_distance: new_status = py_trees.common.Status.SUCCESS if GameTime.get_time() - self._start_time > self._duration: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ On termination of this behavior, the throttle should be set back to 0., to avoid further acceleration. """ if self._type == 'vehicle': self._control.throttle = 0.0 elif self._type == 'walker': self._control.speed = 0.0 if self._actor is not None and self._actor.is_alive: self._actor.apply_control(self._control) super(KeepVelocity, self).terminate(new_status) class ChangeAutoPilot(AtomicBehavior): """ This class contains an atomic behavior to disable/enable the use of the autopilot. Important parameters: - actor: CARLA actor to execute the behavior - activate: True (=enable autopilot) or False (=disable autopilot) - lane_change: Traffic Manager parameter. True (=enable lane changes) or False (=disable lane changes) - distance_between_vehicles: Traffic Manager parameter - max_speed: Traffic Manager parameter. Max speed of the actor. This will only work for road segments with the same speed limit as the first one The behavior terminates after changing the autopilot state """ def __init__(self, actor, activate, parameters=None, name="ChangeAutoPilot"): """ Setup parameters """ super(ChangeAutoPilot, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._activate = activate self._tm = CarlaDataProvider.get_client().get_trafficmanager( CarlaDataProvider.get_traffic_manager_port()) self._parameters = parameters def update(self): """ De/activate autopilot """ self._actor.set_autopilot(self._activate) if self._parameters is not None: if "auto_lane_change" in self._parameters: lane_change = self._parameters["auto_lane_change"] self._tm.auto_lane_change(self._actor, lane_change) if "max_speed" in self._parameters: max_speed = self._parameters["max_speed"] max_road_speed = self._actor.get_speed_limit() if max_road_speed is not None: percentage = (max_road_speed - max_speed) / max_road_speed * 100.0 self._tm.vehicle_percentage_speed_difference(self._actor, percentage) else: print("ChangeAutopilot: Unable to find the vehicle's speed limit") if "distance_between_vehicles" in self._parameters: dist_vehicles = self._parameters["distance_between_vehicles"] self._tm.distance_to_leading_vehicle(self._actor, dist_vehicles) if "force_lane_change" in self._parameters: force_lane_change = self._parameters["force_lane_change"] self._tm.force_lane_change(self._actor, force_lane_change) if "ignore_vehicles_percentage" in self._parameters: ignore_vehicles = self._parameters["ignore_vehicles_percentage"] self._tm.ignore_vehicles_percentage(self._actor, ignore_vehicles) new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class StopVehicle(AtomicBehavior): """ This class contains an atomic stopping behavior. The controlled traffic participant will decelerate with _bake_value_ until reaching a full stop. Important parameters: - actor: CARLA actor to execute the behavior - brake_value: Brake value in [0,1] applied The behavior terminates when the actor stopped moving """ def __init__(self, actor, brake_value, name="Stopping"): """ Setup _actor and maximum braking value """ super(StopVehicle, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) if self._type == 'walker': self._control.speed = 0 self._brake_value = brake_value def update(self): """ Set brake to brake_value until reaching full stop """ new_status = py_trees.common.Status.RUNNING if self._type == 'vehicle': if CarlaDataProvider.get_velocity(self._actor) > EPSILON: self._control.brake = self._brake_value else: new_status = py_trees.common.Status.SUCCESS self._control.brake = 0 else: new_status = py_trees.common.Status.SUCCESS self._actor.apply_control(self._control) self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class SyncArrival(AtomicBehavior): """ This class contains an atomic behavior to set velocity of actor so that it reaches location at the same time as actor_reference. The behavior assumes that the two actors are moving towards location in a straight line. Important parameters: - actor: CARLA actor to execute the behavior - actor_reference: Reference actor with which arrival is synchronized - target_location: CARLA location where the actors should "meet" - gain[optional]: Coefficient for actor's throttle and break controls Note: In parallel to this behavior a termination behavior has to be used to keep continue synchronization for a certain duration, or for a certain distance, etc. """ def __init__(self, actor, actor_reference, target_location, gain=1, name="SyncArrival"): """ Setup required parameters """ super(SyncArrival, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control = carla.VehicleControl() self._actor_reference = actor_reference self._target_location = target_location self._gain = gain self._control.steering = 0 def update(self): """ Dynamic control update for actor velocity """ new_status = py_trees.common.Status.RUNNING distance_reference = calculate_distance(CarlaDataProvider.get_location(self._actor_reference), self._target_location) distance = calculate_distance(CarlaDataProvider.get_location(self._actor), self._target_location) velocity_reference = CarlaDataProvider.get_velocity(self._actor_reference) time_reference = float('inf') if velocity_reference > 0: time_reference = distance_reference / velocity_reference velocity_current = CarlaDataProvider.get_velocity(self._actor) time_current = float('inf') if velocity_current > 0: time_current = distance / velocity_current control_value = (self._gain) * (time_current - time_reference) if control_value > 0: self._control.throttle = min([control_value, 1]) self._control.brake = 0 else: self._control.throttle = 0 self._control.brake = min([abs(control_value), 1]) self._actor.apply_control(self._control) self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ On termination of this behavior, the throttle should be set back to 0., to avoid further acceleration. """ if self._actor is not None and self._actor.is_alive: self._control.throttle = 0.0 self._control.brake = 0.0 self._actor.apply_control(self._control) super(SyncArrival, self).terminate(new_status) class AddNoiseToVehicle(AtomicBehavior): """ This class contains an atomic jitter behavior. To add noise to steer as well as throttle of the vehicle. Important parameters: - actor: CARLA actor to execute the behavior - steer_value: Applied steering noise in [0,1] - throttle_value: Applied throttle noise in [0,1] The behavior terminates after setting the new actor controls """ def __init__(self, actor, steer_value, throttle_value, name="Jittering"): """ Setup actor , maximum steer value and throttle value """ super(AddNoiseToVehicle, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control = carla.VehicleControl() self._steer_value = steer_value self._throttle_value = throttle_value def update(self): """ Set steer to steer_value and throttle to throttle_value until reaching full stop """ self._control = self._actor.get_control() self._control.steer = self._steer_value self._control.throttle = self._throttle_value new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) self._actor.apply_control(self._control) return new_status class ChangeNoiseParameters(AtomicBehavior): """ This class contains an atomic jitter behavior. To add noise to steer as well as throttle of the vehicle. This behavior should be used in conjuction with AddNoiseToVehicle The behavior terminates after one iteration """ def __init__(self, new_steer_noise, new_throttle_noise, noise_mean, noise_std, dynamic_mean_for_steer, dynamic_mean_for_throttle, name="ChangeJittering"): """ Setup actor , maximum steer value and throttle value """ super(ChangeNoiseParameters, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._new_steer_noise = new_steer_noise self._new_throttle_noise = new_throttle_noise self._noise_mean = noise_mean self._noise_std = noise_std self._dynamic_mean_for_steer = dynamic_mean_for_steer self._dynamic_mean_for_throttle = dynamic_mean_for_throttle self._noise_to_apply = abs(random.gauss(self._noise_mean, self._noise_std)) def update(self): """ Change the noise parameters from the structure copy that it receives. """ self._new_steer_noise[0] = min(0, -(self._noise_to_apply - self._dynamic_mean_for_steer)) self._new_throttle_noise[0] = min(self._noise_to_apply + self._dynamic_mean_for_throttle, 1) new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class BasicAgentBehavior(AtomicBehavior): """ This class contains an atomic behavior, which uses the basic_agent from CARLA to control the actor until reaching a target location. Important parameters: - actor: CARLA actor to execute the behavior - target_location: Is the desired target location (carla.location), the actor should move to The behavior terminates after reaching the target_location (within 2 meters) """ _acceptable_target_distance = 2 def __init__(self, actor, target_location, name="BasicAgentBehavior"): """ Setup actor and maximum steer value """ super(BasicAgentBehavior, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._agent = BasicAgent(actor) # pylint: disable=undefined-variable self._agent.set_destination((target_location.x, target_location.y, target_location.z)) self._control = carla.VehicleControl() self._target_location = target_location def update(self): new_status = py_trees.common.Status.RUNNING self._control = self._agent.run_step() location = CarlaDataProvider.get_location(self._actor) if calculate_distance(location, self._target_location) < self._acceptable_target_distance: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) self._actor.apply_control(self._control) return new_status def terminate(self, new_status): self._control.throttle = 0.0 self._control.brake = 0.0 self._actor.apply_control(self._control) super(BasicAgentBehavior, self).terminate(new_status) class Idle(AtomicBehavior): """ This class contains an idle behavior scenario Important parameters: - duration[optional]: Duration in seconds of this behavior A termination can be enforced by providing a duration value. Alternatively, a parallel termination behavior has to be used. """ def __init__(self, duration=float("inf"), name="Idle"): """ Setup actor """ super(Idle, self).__init__(name) self._duration = duration self._start_time = 0 self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def initialise(self): """ Set start time """ self._start_time = GameTime.get_time() super(Idle, self).initialise() def update(self): """ Keep running until termination condition is satisfied """ new_status = py_trees.common.Status.RUNNING if GameTime.get_time() - self._start_time > self._duration: new_status = py_trees.common.Status.SUCCESS return new_status class WaypointFollower(AtomicBehavior): """ This is an atomic behavior to follow waypoints while maintaining a given speed. If no plan is provided, the actor will follow its foward waypoints indefinetely. Otherwise, the behavior will end with SUCCESS upon reaching the end of the plan. If no target velocity is provided, the actor continues with its current velocity. Args: actor (carla.Actor): CARLA actor to execute the behavior. target_speed (float, optional): Desired speed of the actor in m/s. Defaults to None. plan ([carla.Location] or [(carla.Waypoint, carla.agent.navigation.local_planner)], optional): Waypoint plan the actor should follow. Defaults to None. blackboard_queue_name (str, optional): Blackboard variable name, if additional actors should be created on-the-fly. Defaults to None. avoid_collision (bool, optional): Enable/Disable(=default) collision avoidance for vehicles/bikes. Defaults to False. name (str, optional): Name of the behavior. Defaults to "FollowWaypoints". Attributes: actor (carla.Actor): CARLA actor to execute the behavior. name (str, optional): Name of the behavior. _target_speed (float, optional): Desired speed of the actor in m/s. Defaults to None. _plan ([carla.Location] or [(carla.Waypoint, carla.agent.navigation.local_planner)]): Waypoint plan the actor should follow. Defaults to None. _blackboard_queue_name (str): Blackboard variable name, if additional actors should be created on-the-fly. Defaults to None. _avoid_collision (bool): Enable/Disable(=default) collision avoidance for vehicles/bikes. Defaults to False. _actor_dict: Dictonary of all actors, and their corresponding plans (e.g. {actor: plan}). _local_planner_dict: Dictonary of all actors, and their corresponding local planners. Either "Walker" for pedestrians, or a carla.agent.navigation.LocalPlanner for other actors. _args_lateral_dict: Parameters for the PID of the used carla.agent.navigation.LocalPlanner. _unique_id: Unique ID of the behavior based on timestamp in nanoseconds. Note: OpenScenario: The WaypointFollower atomic must be called with an individual name if multiple consecutive WFs. Blackboard variables with lists are used for consecutive WaypointFollower behaviors. Termination of active WaypointFollowers in initialise of AtomicBehavior because any following behavior must terminate the WaypointFollower. """ def __init__(self, actor, target_speed=None, plan=None, blackboard_queue_name=None, avoid_collision=False, name="FollowWaypoints"): """ Set up actor and local planner """ super(WaypointFollower, self).__init__(name, actor) self._actor_dict = {} self._actor_dict[actor] = None self._target_speed = target_speed self._local_planner_dict = {} self._local_planner_dict[actor] = None self._plan = plan self._blackboard_queue_name = blackboard_queue_name if blackboard_queue_name is not None: self._queue = Blackboard().get(blackboard_queue_name) self._args_lateral_dict = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05} self._avoid_collision = avoid_collision self._unique_id = 0 def initialise(self): """ Delayed one-time initialization Checks if another WaypointFollower behavior is already running for this actor. If this is the case, a termination signal is sent to the running behavior. """ super(WaypointFollower, self).initialise() self._unique_id = int(round(time.time() * 1e9)) try: # check whether WF for this actor is already running and add new WF to running_WF list check_attr = operator.attrgetter("running_WF_actor_{}".format(self._actor.id)) running = check_attr(py_trees.blackboard.Blackboard()) active_wf = copy.copy(running) active_wf.append(self._unique_id) py_trees.blackboard.Blackboard().set( "running_WF_actor_{}".format(self._actor.id), active_wf, overwrite=True) except AttributeError: # no WF is active for this actor py_trees.blackboard.Blackboard().set("terminate_WF_actor_{}".format(self._actor.id), [], overwrite=True) py_trees.blackboard.Blackboard().set( "running_WF_actor_{}".format(self._actor.id), [self._unique_id], overwrite=True) for actor in self._actor_dict: self._apply_local_planner(actor) return True def _apply_local_planner(self, actor): """ Convert the plan into locations for walkers (pedestrians), or to a waypoint list for other actors. For non-walkers, activate the carla.agent.navigation.LocalPlanner module. """ if self._target_speed is None: self._target_speed = CarlaDataProvider.get_velocity(actor) else: self._target_speed = self._target_speed if isinstance(actor, carla.Walker): self._local_planner_dict[actor] = "Walker" if self._plan is not None: if isinstance(self._plan[0], carla.Location): self._actor_dict[actor] = self._plan else: self._actor_dict[actor] = [element[0].transform.location for element in self._plan] else: local_planner = LocalPlanner( # pylint: disable=undefined-variable actor, opt_dict={ 'target_speed': self._target_speed * 3.6, 'lateral_control_dict': self._args_lateral_dict}) if self._plan is not None: if isinstance(self._plan[0], carla.Location): plan = [] for location in self._plan: waypoint = CarlaDataProvider.get_map().get_waypoint(location, project_to_road=True, lane_type=carla.LaneType.Any) plan.append((waypoint, RoadOption.LANEFOLLOW)) local_planner.set_global_plan(plan) else: local_planner.set_global_plan(self._plan) self._local_planner_dict[actor] = local_planner self._actor_dict[actor] = self._plan def update(self): """ Compute next control step for the given waypoint plan, obtain and apply control to actor """ new_status = py_trees.common.Status.RUNNING check_term = operator.attrgetter("terminate_WF_actor_{}".format(self._actor.id)) terminate_wf = check_term(py_trees.blackboard.Blackboard()) check_run = operator.attrgetter("running_WF_actor_{}".format(self._actor.id)) active_wf = check_run(py_trees.blackboard.Blackboard()) # Termination of WF if the WFs unique_id is listed in terminate_wf # only one WF should be active, therefore all previous WF have to be terminated if self._unique_id in terminate_wf: terminate_wf.remove(self._unique_id) if self._unique_id in active_wf: active_wf.remove(self._unique_id) py_trees.blackboard.Blackboard().set( "terminate_WF_actor_{}".format(self._actor.id), terminate_wf, overwrite=True) py_trees.blackboard.Blackboard().set( "running_WF_actor_{}".format(self._actor.id), active_wf, overwrite=True) new_status = py_trees.common.Status.SUCCESS return new_status if self._blackboard_queue_name is not None: while not self._queue.empty(): actor = self._queue.get() if actor is not None and actor not in self._actor_dict: self._apply_local_planner(actor) success = True for actor in self._local_planner_dict: local_planner = self._local_planner_dict[actor] if actor else None if actor is not None and actor.is_alive and local_planner is not None: # Check if the actor is a vehicle/bike if not isinstance(actor, carla.Walker): control = local_planner.run_step(debug=False) if self._avoid_collision and detect_lane_obstacle(actor): control.throttle = 0.0 control.brake = 1.0 actor.apply_control(control) # Check if the actor reached the end of the plan # replace access to private _waypoints_queue with public getter if local_planner._waypoints_queue: # pylint: disable=protected-access success = False # If the actor is a pedestrian, we have to use the WalkerAIController # The walker is sent to the next waypoint in its plan else: actor_location = CarlaDataProvider.get_location(actor) success = False if self._actor_dict[actor]: location = self._actor_dict[actor][0] direction = location - actor_location direction_norm = math.sqrt(direction.x**2 + direction.y**2) control = actor.get_control() control.speed = self._target_speed control.direction = direction / direction_norm actor.apply_control(control) if direction_norm < 1.0: self._actor_dict[actor] = self._actor_dict[actor][1:] if self._actor_dict[actor] is None: success = True else: control = actor.get_control() control.speed = self._target_speed control.direction = CarlaDataProvider.get_transform(actor).rotation.get_forward_vector() actor.apply_control(control) if success: new_status = py_trees.common.Status.SUCCESS return new_status def terminate(self, new_status): """ On termination of this behavior, the controls should be set back to 0. """ for actor in self._local_planner_dict: if actor is not None and actor.is_alive: control, _ = get_actor_control(actor) actor.apply_control(control) local_planner = self._local_planner_dict[actor] if local_planner is not None and local_planner != "Walker": local_planner.reset_vehicle() local_planner = None self._local_planner_dict = {} self._actor_dict = {} super(WaypointFollower, self).terminate(new_status) class LaneChange(WaypointFollower): """ This class inherits from the class WaypointFollower. This class contains an atomic lane change behavior to a parallel lane. The vehicle follows a waypoint plan to the other lane, which is calculated in the initialise method. This waypoint plan is calculated with a scenario helper function. Important parameters: - actor: CARLA actor to execute the behavior - speed: speed of the actor for the lane change, in m/s - direction: 'right' or 'left', depending on which lane to change - distance_same_lane: straight distance before lane change, in m - distance_other_lane: straight distance after lane change, in m - distance_lane_change: straight distance for the lane change itself, in m The total distance driven is greater than the sum of distance_same_lane and distance_other_lane. It results from the lane change distance plus the distance_same_lane plus distance_other_lane. The lane change distance is set to 25m (straight), the driven distance is slightly greater. A parallel termination behavior has to be used. """ def __init__(self, actor, speed=10, direction='left', distance_same_lane=5, distance_other_lane=100, distance_lane_change=25, name='LaneChange'): self._direction = direction self._distance_same_lane = distance_same_lane self._distance_other_lane = distance_other_lane self._distance_lane_change = distance_lane_change self._target_lane_id = None self._distance_new_lane = 0 self._pos_before_lane_change = None super(LaneChange, self).__init__(actor, target_speed=speed, name=name) def initialise(self): # get start position position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location()) # calculate plan with scenario_helper function self._plan, self._target_lane_id = generate_target_waypoint_list_multilane( position_actor, self._direction, self._distance_same_lane, self._distance_other_lane, self._distance_lane_change, check='true') super(LaneChange, self).initialise() def update(self): status = super(LaneChange, self).update() current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location()) current_lane_id = current_position_actor.lane_id if current_lane_id == self._target_lane_id: # driving on new lane distance = current_position_actor.transform.location.distance(self._pos_before_lane_change) if distance > self._distance_other_lane: # long enough distance on new lane --> SUCCESS status = py_trees.common.Status.SUCCESS else: # no lane change yet self._pos_before_lane_change = current_position_actor.transform.location return status class SetInitSpeed(AtomicBehavior): """ This class contains an atomic behavior to set the init_speed of an actor, succeding immeditely after initializing """ def __init__(self, actor, init_speed=10, name='SetInitSpeed'): self._init_speed = init_speed self._terminate = None self._actor = actor super(SetInitSpeed, self).__init__(name, actor) def initialise(self): """ Initialize it's speed """ transform = self._actor.get_transform() yaw = transform.rotation.yaw * (math.pi / 180) vx = math.cos(yaw) * self._init_speed vy = math.sin(yaw) * self._init_speed self._actor.set_target_velocity(carla.Vector3D(vx, vy, 0)) def update(self): """ Nothing to update, end the behavior """ return py_trees.common.Status.SUCCESS class HandBrakeVehicle(AtomicBehavior): """ This class contains an atomic hand brake behavior. To set the hand brake value of the vehicle. Important parameters: - vehicle: CARLA actor to execute the behavior - hand_brake_value to be applied in [0,1] The behavior terminates after setting the hand brake value """ def __init__(self, vehicle, hand_brake_value, name="Braking"): """ Setup vehicle control and brake value """ super(HandBrakeVehicle, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._vehicle = vehicle self._control, self._type = get_actor_control(vehicle) self._hand_brake_value = hand_brake_value def update(self): """ Set handbrake """ new_status = py_trees.common.Status.SUCCESS if self._type == 'vehicle': self._control.hand_brake = self._hand_brake_value self._vehicle.apply_control(self._control) else: self._hand_brake_value = None self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) self._vehicle.apply_control(self._control) return new_status class ActorDestroy(AtomicBehavior): """ This class contains an actor destroy behavior. Given an actor this behavior will delete it. Important parameters: - actor: CARLA actor to be deleted The behavior terminates after removing the actor """ def __init__(self, actor, name="ActorDestroy"): """ Setup actor """ super(ActorDestroy, self).__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): new_status = py_trees.common.Status.RUNNING if self._actor: CarlaDataProvider.remove_actor_by_id(self._actor.id) self._actor = None new_status = py_trees.common.Status.SUCCESS return new_status class ActorTransformSetter(AtomicBehavior): """ This class contains an atomic behavior to set the transform of an actor. Important parameters: - actor: CARLA actor to execute the behavior - transform: New target transform (position + orientation) of the actor - physics [optional]: If physics is true, the actor physics will be reactivated upon success The behavior terminates when actor is set to the new actor transform (closer than 1 meter) NOTE: It is very important to ensure that the actor location is spawned to the new transform because of the appearence of a rare runtime processing error. WaypointFollower with LocalPlanner, might fail if new_status is set to success before the actor is really positioned at the new transform. Therefore: calculate_distance(actor, transform) < 1 meter """ def __init__(self, actor, transform, physics=True, name="ActorTransformSetter"): """ Init """ super(ActorTransformSetter, self).__init__(name, actor) self._transform = transform self._physics = physics self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def initialise(self): if self._actor.is_alive: self._actor.set_target_velocity(carla.Vector3D(0, 0, 0)) self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) self._actor.set_transform(self._transform) super(ActorTransformSetter, self).initialise() def update(self): """ Transform actor """ new_status = py_trees.common.Status.RUNNING if not self._actor.is_alive: new_status = py_trees.common.Status.FAILURE if calculate_distance(self._actor.get_location(), self._transform.location) < 1.0: if self._physics: self._actor.set_simulate_physics(enabled=True) new_status = py_trees.common.Status.SUCCESS return new_status class TrafficLightStateSetter(AtomicBehavior): """ This class contains an atomic behavior to set the state of a given traffic light Args: actor (carla.TrafficLight): ID of the traffic light that shall be changed state (carla.TrafficLightState): New target state The behavior terminates after trying to set the new state """ def __init__(self, actor, state, name="TrafficLightStateSetter"): """ Init """ super(TrafficLightStateSetter, self).__init__(name) self._actor = actor if "traffic_light" in actor.type_id else None self._state = state self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): """ Change the state of the traffic light """ if self._actor is None: return py_trees.common.Status.FAILURE new_status = py_trees.common.Status.RUNNING if self._actor.is_alive: self._actor.set_state(self._state) new_status = py_trees.common.Status.SUCCESS else: # For some reason the actor is gone... new_status = py_trees.common.Status.FAILURE return new_status class ActorSource(AtomicBehavior): """ Implementation for a behavior that will indefinitely create actors at a given transform if no other actor exists in a given radius from the transform. Important parameters: - actor_type_list: Type of CARLA actors to be spawned - transform: Spawn location - threshold: Min available free distance between other actors and the spawn location - blackboard_queue_name: Name of the blackboard used to control this behavior - actor_limit [optional]: Maximum number of actors to be spawned (default=7) A parallel termination behavior has to be used. """ def __init__(self, actor_type_list, transform, threshold, blackboard_queue_name, actor_limit=7, name="ActorSource"): """ Setup class members """ super(ActorSource, self).__init__(name) self._world = CarlaDataProvider.get_world() self._actor_types = actor_type_list self._spawn_point = transform self._threshold = threshold self._queue = Blackboard().get(blackboard_queue_name) self._actor_limit = actor_limit self._last_blocking_actor = None def update(self): new_status = py_trees.common.Status.RUNNING if self._actor_limit > 0: world_actors = self._world.get_actors() spawn_point_blocked = False if (self._last_blocking_actor and self._spawn_point.location.distance(self._last_blocking_actor.get_location()) < self._threshold): spawn_point_blocked = True if not spawn_point_blocked: for actor in world_actors: if self._spawn_point.location.distance(actor.get_location()) < self._threshold: spawn_point_blocked = True self._last_blocking_actor = actor break if not spawn_point_blocked: try: new_actor = CarlaDataProvider.request_new_actor( np.random.choice(self._actor_types), self._spawn_point) self._actor_limit -= 1 self._queue.put(new_actor) except: # pylint: disable=bare-except print("ActorSource unable to spawn actor") return new_status class ActorSink(AtomicBehavior): """ Implementation for a behavior that will indefinitely destroy actors that wander near a given location within a specified threshold. Important parameters: - actor_type_list: Type of CARLA actors to be spawned - sink_location: Location (carla.location) at which actors will be deleted - threshold: Distance around sink_location in which actors will be deleted A parallel termination behavior has to be used. """ def __init__(self, sink_location, threshold, name="ActorSink"): """ Setup class members """ super(ActorSink, self).__init__(name) self._sink_location = sink_location self._threshold = threshold def update(self): new_status = py_trees.common.Status.RUNNING CarlaDataProvider.remove_actors_in_surrounding(self._sink_location, self._threshold) return new_status class StartRecorder(AtomicBehavior): """ Atomic that starts the CARLA recorder. Only one can be active at a time, and if this isn't the case, the recorder will automatically stop the previous one. Args: recorder_name (str): name of the file to write the recorded data. Remember that a simple name will save the recording in 'CarlaUE4/Saved/'. Otherwise, if some folder appears in the name, it will be considered an absolute path. name (str): name of the behavior """ def __init__(self, recorder_name, name="StartRecorder"): """ Setup class members """ super(StartRecorder, self).__init__(name) self._client = CarlaDataProvider.get_client() self._recorder_name = recorder_name def update(self): self._client.start_recorder(self._recorder_name) return py_trees.common.Status.SUCCESS class StopRecorder(AtomicBehavior): """ Atomic that stops the CARLA recorder. Args: name (str): name of the behavior """ def __init__(self, name="StopRecorder"): """ Setup class members """ super(StopRecorder, self).__init__(name) self._client = CarlaDataProvider.get_client() def update(self): self._client.stop_recorder() return py_trees.common.Status.SUCCESS class TrafficLightManipulator(AtomicBehavior): """ Atomic behavior that manipulates traffic lights around the ego_vehicle to trigger scenarios 7 to 10. This is done by setting 2 of the traffic light at the intersection to green (with some complex precomputation to set everything up). Important parameters: - ego_vehicle: CARLA actor that controls this behavior - subtype: string that gathers information of the route and scenario number (check SUBTYPE_CONFIG_TRANSLATION below) """ RED = carla.TrafficLightState.Red YELLOW = carla.TrafficLightState.Yellow GREEN = carla.TrafficLightState.Green # Time constants RED_TIME = 1.5 # Minimum time the ego vehicle waits in red (seconds) YELLOW_TIME = 2 # Time spent at yellow state (seconds) RESET_TIME = 6 # Time waited before resetting all the junction (seconds) # Experimental values TRIGGER_DISTANCE = 10 # Distance that makes all vehicles in the lane enter the junction (meters) DIST_TO_WAITING_TIME = 0.04 # Used to wait longer at larger intersections (s/m) INT_CONF_OPP1 = {'ego': RED, 'ref': RED, 'left': RED, 'right': RED, 'opposite': GREEN} INT_CONF_OPP2 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': RED, 'opposite': GREEN} INT_CONF_LFT1 = {'ego': RED, 'ref': RED, 'left': GREEN, 'right': RED, 'opposite': RED} INT_CONF_LFT2 = {'ego': GREEN, 'ref': GREEN, 'left': GREEN, 'right': RED, 'opposite': RED} INT_CONF_RGT1 = {'ego': RED, 'ref': RED, 'left': RED, 'right': GREEN, 'opposite': RED} INT_CONF_RGT2 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': GREEN, 'opposite': RED} INT_CONF_REF1 = {'ego': GREEN, 'ref': GREEN, 'left': RED, 'right': RED, 'opposite': RED} INT_CONF_REF2 = {'ego': YELLOW, 'ref': YELLOW, 'left': RED, 'right': RED, 'opposite': RED} # Depending on the scenario, IN ORDER OF IMPORTANCE, the traffic light changed # The list has to contain only items of the INT_CONF SUBTYPE_CONFIG_TRANSLATION = { 'S7left': ['left', 'opposite', 'right'], 'S7right': ['left', 'opposite'], 'S7opposite': ['right', 'left', 'opposite'], 'S8left': ['opposite'], 'S9right': ['left', 'opposite'] } CONFIG_TLM_TRANSLATION = { 'left': [INT_CONF_LFT1, INT_CONF_LFT2], 'right': [INT_CONF_RGT1, INT_CONF_RGT2], 'opposite': [INT_CONF_OPP1, INT_CONF_OPP2] } def __init__(self, ego_vehicle, subtype, debug=False, name="TrafficLightManipulator"): super(TrafficLightManipulator, self).__init__(name) self.ego_vehicle = ego_vehicle self.subtype = subtype self.current_step = 1 self.debug = debug self.traffic_light = None self.annotations = None self.configuration = None self.prev_junction_state = None self.junction_location = None self.seconds_waited = 0 self.prev_time = None self.max_trigger_distance = None self.waiting_time = None self.inside_junction = False self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): new_status = py_trees.common.Status.RUNNING # 1) Set up the parameters if self.current_step == 1: # Traffic light affecting the ego vehicle self.traffic_light = CarlaDataProvider.get_next_traffic_light(self.ego_vehicle, use_cached_location=False) if not self.traffic_light: # nothing else to do in this iteration... return new_status # "Topology" of the intersection self.annotations = CarlaDataProvider.annotate_trafficlight_in_group(self.traffic_light) # Which traffic light will be modified (apart from the ego lane) self.configuration = self.get_traffic_light_configuration(self.subtype, self.annotations) if self.configuration is None: self.current_step = 0 # End the behavior return new_status # Modify the intersection. Store the previous state self.prev_junction_state = self.set_intersection_state(self.INT_CONF_REF1) self.current_step += 1 if self.debug: print("--- All set up") # 2) Modify the ego lane to yellow when closeby elif self.current_step == 2: ego_location = CarlaDataProvider.get_location(self.ego_vehicle) if self.junction_location is None: ego_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location) junction_waypoint = ego_waypoint.next(0.5)[0] while not junction_waypoint.is_junction: next_wp = junction_waypoint.next(0.5) if len(next_wp) > 0: next_wp = next_wp[0] junction_waypoint = next_wp else: break self.junction_location = junction_waypoint.transform.location distance = ego_location.distance(self.junction_location) # Failure check if self.max_trigger_distance is None: self.max_trigger_distance = distance + 1 if distance > self.max_trigger_distance: self.current_step = 0 elif distance < self.TRIGGER_DISTANCE: _ = self.set_intersection_state(self.INT_CONF_REF2) self.current_step += 1 if self.debug: print("--- Distance until traffic light changes: {}".format(distance)) # 3) Modify the ego lane to red and the chosen one to green after several seconds elif self.current_step == 3: if self.passed_enough_time(self.YELLOW_TIME): _ = self.set_intersection_state(self.CONFIG_TLM_TRANSLATION[self.configuration][0]) self.current_step += 1 # 4) Wait a bit to let vehicles enter the intersection, then set the ego lane to green elif self.current_step == 4: # Get the time in red, dependent on the intersection dimensions if self.waiting_time is None: self.waiting_time = self.get_waiting_time(self.annotations, self.configuration) if self.passed_enough_time(self.waiting_time): _ = self.set_intersection_state(self.CONFIG_TLM_TRANSLATION[self.configuration][1]) self.current_step += 1 # 5) Wait for the end of the intersection elif self.current_step == 5: # the traffic light has been manipulated, wait until the vehicle finsihes the intersection ego_location = CarlaDataProvider.get_location(self.ego_vehicle) ego_waypoint = CarlaDataProvider.get_map().get_waypoint(ego_location) if not self.inside_junction: if ego_waypoint.is_junction: # Wait for the ego_vehicle to enter a junction self.inside_junction = True else: if self.debug: print("--- Waiting to ENTER a junction") else: if ego_waypoint.is_junction: if self.debug: print("--- Waiting to EXIT a junction") else: # And to leave it self.inside_junction = False self.current_step += 1 # 6) At the end (or if something failed), reset to the previous state else: if self.prev_junction_state: CarlaDataProvider.reset_lights(self.prev_junction_state) if self.debug: print("--- Returning the intersection to its previous state") self.variable_cleanup() new_status = py_trees.common.Status.SUCCESS return new_status def passed_enough_time(self, time_limit): """ Returns true or false depending on the time that has passed from the first time this function was called """ # Start the timer if self.prev_time is None: self.prev_time = GameTime.get_time() timestamp = GameTime.get_time() self.seconds_waited += (timestamp - self.prev_time) self.prev_time = timestamp if self.debug: print("--- Waited seconds: {}".format(self.seconds_waited)) if self.seconds_waited >= time_limit: self.seconds_waited = 0 self.prev_time = None return True return False def set_intersection_state(self, choice): """ Changes the intersection to the desired state """ prev_state = CarlaDataProvider.update_light_states( self.traffic_light, self.annotations, choice, freeze=True) return prev_state def get_waiting_time(self, annotation, direction): """ Calculates the time the ego traffic light will remain red to let vehicles enter the junction """ tl = annotation[direction][0] ego_tl = annotation["ref"][0] tl_location = CarlaDataProvider.get_trafficlight_trigger_location(tl) ego_tl_location = CarlaDataProvider.get_trafficlight_trigger_location(ego_tl) distance = ego_tl_location.distance(tl_location) return self.RED_TIME + distance * self.DIST_TO_WAITING_TIME def get_traffic_light_configuration(self, subtype, annotations): """ Checks the list of possible altered traffic lights and gets the first one that exists in the intersection Important parameters: - subtype: Subtype of the scenario - annotations: list of the traffic light of the junction, with their direction (right, left...) """ configuration = None if subtype in self.SUBTYPE_CONFIG_TRANSLATION: possible_configurations = self.SUBTYPE_CONFIG_TRANSLATION[self.subtype] while possible_configurations: # Chose the first one and delete it configuration = possible_configurations[0] possible_configurations = possible_configurations[1:] if configuration in annotations: if annotations[configuration]: # Found a valid configuration break else: # The traffic light doesn't exist, get another one configuration = None else: if self.debug: print("This configuration name is wrong") configuration = None if configuration is None and self.debug: print("This subtype has no traffic light available") else: if self.debug: print("This subtype is unknown") return configuration def variable_cleanup(self): """ Resets all variables to the intial state """ self.current_step = 1 self.traffic_light = None self.annotations = None self.configuration = None self.prev_junction_state = None self.junction_location = None self.max_trigger_distance = None self.waiting_time = None self.inside_junction = False class ScenarioTriggerer(AtomicBehavior): """ Handles the triggering of the scenarios that are part of a route. Initializes a list of blackboard variables to False, and only sets them to True when the ego vehicle is very close to the scenarios """ WINDOWS_SIZE = 5 def __init__(self, actor, route, blackboard_list, distance, repeat_scenarios=False, debug=False, name="ScenarioTriggerer"): """ Setup class members """ super(ScenarioTriggerer, self).__init__(name) self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map() self._repeat = repeat_scenarios self._debug = debug self._actor = actor self._route = route self._distance = distance self._blackboard_list = blackboard_list self._triggered_scenarios = [] # List of already done scenarios self._current_index = 0 self._route_length = len(self._route) self._waypoints, _ = zip(*self._route) def update(self): new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status lower_bound = self._current_index upper_bound = min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length) shortest_distance = float('inf') closest_index = -1 for index in range(lower_bound, upper_bound): ref_waypoint = self._waypoints[index] ref_location = ref_waypoint.location dist_to_route = ref_location.distance(location) if dist_to_route <= shortest_distance: closest_index = index shortest_distance = dist_to_route if closest_index == -1 or shortest_distance == float('inf'): return new_status # Update the ego position at the route self._current_index = closest_index route_location = self._waypoints[closest_index].location # Check which scenarios can be triggered blackboard = py_trees.blackboard.Blackboard() for black_var_name, scen_location in self._blackboard_list: # Close enough scen_distance = route_location.distance(scen_location) condition1 = bool(scen_distance < self._distance) # Not being currently done value = blackboard.get(black_var_name) condition2 = bool(not value) # Already done, if needed condition3 = bool(self._repeat or black_var_name not in self._triggered_scenarios) if condition1 and condition2 and condition3: _ = blackboard.set(black_var_name, True) self._triggered_scenarios.append(black_var_name) if self._debug: self._world.debug.draw_point( scen_location + carla.Location(z=4), size=0.5, life_time=0.5, color=carla.Color(255, 255, 0) ) self._world.debug.draw_string( scen_location + carla.Location(z=5), str(black_var_name), False, color=carla.Color(0, 0, 0), life_time=1000 ) return new_status ================================================ FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_criteria.py ================================================ #!/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 atomic evaluation criteria required to analyze if a scenario was completed successfully or failed. Criteria should run continuously to monitor the state of a single actor, multiple actors or environmental parameters. Hence, a termination is not required. The atomic criteria are implemented with py_trees. """ import weakref import math import numpy as np import py_trees import shapely import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import GameTime from srunner.scenariomanager.traffic_events import TrafficEvent, TrafficEventType class Criterion(py_trees.behaviour.Behaviour): """ Base class for all criteria used to evaluate a scenario for success/failure Important parameters (PUBLIC): - name: Name of the criterion - expected_value_success: Result in case of success (e.g. max_speed, zero collisions, ...) - expected_value_acceptable: Result that does not mean a failure, but is not good enough for a success - actual_value: Actual result after running the scenario - test_status: Used to access the result of the criterion - optional: Indicates if a criterion is optional (not used for overall analysis) """ def __init__(self, name, actor, expected_value_success, expected_value_acceptable=None, optional=False, terminate_on_failure=False): super(Criterion, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._terminate_on_failure = terminate_on_failure self.name = name self.actor = actor self.test_status = "INIT" self.expected_value_success = expected_value_success self.expected_value_acceptable = expected_value_acceptable self.actual_value = 0 self.optional = optional self.list_traffic_events = [] def initialise(self): """ Initialise the criterion. Can be extended by the user-derived class """ self.logger.debug("%s.initialise()" % (self.__class__.__name__)) def terminate(self, new_status): """ Terminate the criterion. Can be extended by the user-derived class """ if (self.test_status == "RUNNING") or (self.test_status == "INIT"): self.test_status = "SUCCESS" self.logger.debug("%s.terminate()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) class MaxVelocityTest(Criterion): """ This class contains an atomic test for maximum velocity. Important parameters: - actor: CARLA actor to be used for this test - max_velocity_allowed: maximum allowed velocity in m/s - optional [optional]: If True, the result is not considered for an overall pass/fail result """ def __init__(self, actor, max_velocity_allowed, optional=False, name="CheckMaximumVelocity"): """ Setup actor and maximum allowed velovity """ super(MaxVelocityTest, self).__init__(name, actor, max_velocity_allowed, None, optional) def update(self): """ Check velocity """ new_status = py_trees.common.Status.RUNNING if self.actor is None: return new_status velocity = CarlaDataProvider.get_velocity(self.actor) self.actual_value = max(velocity, self.actual_value) if velocity > self.expected_value_success: self.test_status = "FAILURE" else: self.test_status = "SUCCESS" if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class DrivenDistanceTest(Criterion): """ This class contains an atomic test to check the driven distance Important parameters: - actor: CARLA actor to be used for this test - distance_success: If the actor's driven distance is more than this value (in meters), the test result is SUCCESS - distance_acceptable: If the actor's driven distance is more than this value (in meters), the test result is ACCEPTABLE - optional [optional]: If True, the result is not considered for an overall pass/fail result """ def __init__(self, actor, distance_success, distance_acceptable=None, optional=False, name="CheckDrivenDistance"): """ Setup actor """ super(DrivenDistanceTest, self).__init__(name, actor, distance_success, distance_acceptable, optional) self._last_location = None def initialise(self): self._last_location = CarlaDataProvider.get_location(self.actor) super(DrivenDistanceTest, self).initialise() def update(self): """ Check distance """ new_status = py_trees.common.Status.RUNNING if self.actor is None: return new_status location = CarlaDataProvider.get_location(self.actor) if location is None: return new_status if self._last_location is None: self._last_location = location return new_status self.actual_value += location.distance(self._last_location) self._last_location = location if self.actual_value > self.expected_value_success: self.test_status = "SUCCESS" elif (self.expected_value_acceptable is not None and self.actual_value > self.expected_value_acceptable): self.test_status = "ACCEPTABLE" else: self.test_status = "RUNNING" if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ Set final status """ if self.test_status != "SUCCESS": self.test_status = "FAILURE" self.actual_value = round(self.actual_value, 2) super(DrivenDistanceTest, self).terminate(new_status) class AverageVelocityTest(Criterion): """ This class contains an atomic test for average velocity. Important parameters: - actor: CARLA actor to be used for this test - avg_velocity_success: If the actor's average velocity is more than this value (in m/s), the test result is SUCCESS - avg_velocity_acceptable: If the actor's average velocity is more than this value (in m/s), the test result is ACCEPTABLE - optional [optional]: If True, the result is not considered for an overall pass/fail result """ def __init__(self, actor, avg_velocity_success, avg_velocity_acceptable=None, optional=False, name="CheckAverageVelocity"): """ Setup actor and average velovity expected """ super(AverageVelocityTest, self).__init__(name, actor, avg_velocity_success, avg_velocity_acceptable, optional) self._last_location = None self._distance = 0.0 def initialise(self): self._last_location = CarlaDataProvider.get_location(self.actor) super(AverageVelocityTest, self).initialise() def update(self): """ Check velocity """ new_status = py_trees.common.Status.RUNNING if self.actor is None: return new_status location = CarlaDataProvider.get_location(self.actor) if location is None: return new_status if self._last_location is None: self._last_location = location return new_status self._distance += location.distance(self._last_location) self._last_location = location elapsed_time = GameTime.get_time() if elapsed_time > 0.0: self.actual_value = self._distance / elapsed_time if self.actual_value > self.expected_value_success: self.test_status = "SUCCESS" elif (self.expected_value_acceptable is not None and self.actual_value > self.expected_value_acceptable): self.test_status = "ACCEPTABLE" else: self.test_status = "RUNNING" if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ Set final status """ if self.test_status == "RUNNING": self.test_status = "FAILURE" super(AverageVelocityTest, self).terminate(new_status) class CollisionTest(Criterion): """ This class contains an atomic test for collisions. Args: - actor (carla.Actor): CARLA actor to be used for this test - other_actor (carla.Actor): only collisions with this actor will be registered - other_actor_type (str): only collisions with actors including this type_id will count. Additionally, the "miscellaneous" tag can also be used to include all static objects in the scene - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test - optional [optional]: If True, the result is not considered for an overall pass/fail result """ MIN_AREA_OF_COLLISION = 3 # If closer than this distance, the collision is ignored MAX_AREA_OF_COLLISION = 5 # If further than this distance, the area is forgotten MAX_ID_TIME = 5 # Amount of time the last collision if is remembered def __init__(self, actor, other_actor=None, other_actor_type=None, optional=False, name="CollisionTest", terminate_on_failure=False): """ Construction with sensor setup """ super(CollisionTest, self).__init__(name, actor, 0, None, optional, terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) world = self.actor.get_world() blueprint = world.get_blueprint_library().find('sensor.other.collision') self._collision_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor) self._collision_sensor.listen(lambda event: self._count_collisions(weakref.ref(self), event)) self.other_actor = other_actor self.other_actor_type = other_actor_type self.registered_collisions = [] self.last_id = None self.collision_time = None def update(self): """ Check collision count """ new_status = py_trees.common.Status.RUNNING if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE actor_location = CarlaDataProvider.get_location(self.actor) new_registered_collisions = [] # Loops through all the previous registered collisions for collision_location in self.registered_collisions: # Get the distance to the collision point distance_vector = actor_location - collision_location distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2)) # If far away from a previous collision, forget it if distance <= self.MAX_AREA_OF_COLLISION: new_registered_collisions.append(collision_location) self.registered_collisions = new_registered_collisions if self.last_id and GameTime.get_time() - self.collision_time > self.MAX_ID_TIME: self.last_id = None self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ Cleanup sensor """ if self._collision_sensor is not None: self._collision_sensor.destroy() self._collision_sensor = None super(CollisionTest, self).terminate(new_status) @staticmethod def _count_collisions(weak_self, event): # pylint: disable=too-many-return-statements """ Callback to update collision count """ self = weak_self() if not self: return actor_location = CarlaDataProvider.get_location(self.actor) # Ignore the current one if it is the same id as before if self.last_id == event.other_actor.id: return # Filter to only a specific actor if self.other_actor and self.other_actor.id != event.other_actor.id: return # Filter to only a specific type if self.other_actor_type: if self.other_actor_type == "miscellaneous": if "traffic" not in event.other_actor.type_id \ and "static" not in event.other_actor.type_id: return else: if self.other_actor_type not in event.other_actor.type_id: return # Ignore it if its too close to a previous collision (avoid micro collisions) for collision_location in self.registered_collisions: distance_vector = actor_location - collision_location distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2)) if distance <= self.MIN_AREA_OF_COLLISION: return if ('static' in event.other_actor.type_id or 'traffic' in event.other_actor.type_id) \ and 'sidewalk' not in event.other_actor.type_id: actor_type = TrafficEventType.COLLISION_STATIC elif 'vehicle' in event.other_actor.type_id: actor_type = TrafficEventType.COLLISION_VEHICLE elif 'walker' in event.other_actor.type_id: actor_type = TrafficEventType.COLLISION_PEDESTRIAN else: return collision_event = TrafficEvent(event_type=actor_type) collision_event.set_dict({ 'type': event.other_actor.type_id, 'id': event.other_actor.id, 'x': actor_location.x, 'y': actor_location.y, 'z': actor_location.z}) collision_event.set_message( "Agent collided against object with type={} and id={} at (x={}, y={}, z={}, t={})".format( event.other_actor.type_id, event.other_actor.id, round(actor_location.x, 3), round(actor_location.y, 3), round(actor_location.z, 3), CarlaDataProvider.get_time_step())) self.test_status = "FAILURE" self.actual_value += 1 self.collision_time = GameTime.get_time() self.registered_collisions.append(actor_location) self.list_traffic_events.append(collision_event) # Number 0: static objects -> ignore it if event.other_actor.id != 0: self.last_id = event.other_actor.id class ActorSpeedAboveThresholdTest(Criterion): """ This test will fail if the actor has had its linear velocity lower than a specific value for a specific amount of time Important parameters: - actor: CARLA actor to be used for this test - speed_threshold: speed required - below_threshold_max_time: Maximum time (in seconds) the actor can remain under the speed threshold - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ def __init__(self, actor, speed_threshold, below_threshold_max_time, name="ActorSpeedAboveThresholdTest", terminate_on_failure=False): """ Class constructor. """ super(ActorSpeedAboveThresholdTest, self).__init__(name, actor, 0, terminate_on_failure=terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._speed_threshold = speed_threshold self._below_threshold_max_time = below_threshold_max_time self._time_last_valid_state = None def update(self): """ Check if the actor speed is above the speed_threshold """ new_status = py_trees.common.Status.RUNNING linear_speed = CarlaDataProvider.get_velocity(self._actor) if linear_speed is not None: if linear_speed < self._speed_threshold and self._time_last_valid_state: if (GameTime.get_time() - self._time_last_valid_state) > self._below_threshold_max_time: # Game over. The actor has been "blocked" for too long self.test_status = "FAILURE" # record event vehicle_location = CarlaDataProvider.get_location(self._actor) blocked_event = TrafficEvent(event_type=TrafficEventType.VEHICLE_BLOCKED) ActorSpeedAboveThresholdTest._set_event_message(blocked_event, vehicle_location) ActorSpeedAboveThresholdTest._set_event_dict(blocked_event, vehicle_location) self.list_traffic_events.append(blocked_event) else: self._time_last_valid_state = GameTime.get_time() if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status @staticmethod def _set_event_message(event, location): """ Sets the message of the event """ event.set_message('Agent got blocked at (x={}, y={}, z={}, t={})'.format(round(location.x, 3), round(location.y, 3), round(location.z, 3), CarlaDataProvider.get_time_step())) @staticmethod def _set_event_dict(event, location): """ Sets the dictionary of the event """ event.set_dict({ 'x': location.x, 'y': location.y, 'z': location.z, }) class KeepLaneTest(Criterion): """ This class contains an atomic test for keeping lane. Important parameters: - actor: CARLA actor to be used for this test - optional [optional]: If True, the result is not considered for an overall pass/fail result """ def __init__(self, actor, optional=False, name="CheckKeepLane"): """ Construction with sensor setup """ super(KeepLaneTest, self).__init__(name, actor, 0, None, optional) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) world = self.actor.get_world() blueprint = world.get_blueprint_library().find('sensor.other.lane_invasion') self._lane_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor) self._lane_sensor.listen(lambda event: self._count_lane_invasion(weakref.ref(self), event)) def update(self): """ Check lane invasion count """ new_status = py_trees.common.Status.RUNNING if self.actual_value > 0: self.test_status = "FAILURE" else: self.test_status = "SUCCESS" if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ Cleanup sensor """ if self._lane_sensor is not None: self._lane_sensor.destroy() self._lane_sensor = None super(KeepLaneTest, self).terminate(new_status) @staticmethod def _count_lane_invasion(weak_self, event): """ Callback to update lane invasion count """ self = weak_self() if not self: return self.actual_value += 1 class ReachedRegionTest(Criterion): """ This class contains the reached region test The test is a success if the actor reaches a specified region Important parameters: - actor: CARLA actor to be used for this test - min_x, max_x, min_y, max_y: Bounding box of the checked region """ def __init__(self, actor, min_x, max_x, min_y, max_y, name="ReachedRegionTest"): """ Setup trigger region (rectangle provided by [min_x,min_y] and [max_x,max_y] """ super(ReachedRegionTest, self).__init__(name, actor, 0) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._min_x = min_x self._max_x = max_x self._min_y = min_y self._max_y = max_y def update(self): """ Check if the actor location is within trigger region """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status in_region = False if self.test_status != "SUCCESS": in_region = (location.x > self._min_x and location.x < self._max_x) and ( location.y > self._min_y and location.y < self._max_y) if in_region: self.test_status = "SUCCESS" else: self.test_status = "RUNNING" if self.test_status == "SUCCESS": new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class OffRoadTest(Criterion): """ Atomic containing a test to detect when an actor deviates from the driving lanes. This atomic can fail when actor has spent a specific time outside driving lanes (defined by OpenDRIVE). Simplified version of OnSidewalkTest, and doesn't relly on waypoints with *Sidewalk* lane types Args: actor (carla.Actor): CARLA actor to be used for this test duration (float): Time spent at sidewalks before the atomic fails. If terminate_on_failure isn't active, this is ignored. optional (bool): If True, the result is not considered for an overall pass/fail result when using the output argument terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met. """ def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name="OffRoadTest"): """ Setup of the variables """ super(OffRoadTest, self).__init__(name, actor, 0, None, optional, terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._map = CarlaDataProvider.get_map() self._offroad = False self._duration = duration self._prev_time = None self._time_offroad = 0 def update(self): """ First, transforms the actor's current position to its corresponding waypoint. This is filtered to only use waypoints of type Driving or Parking. Depending on these results, the actor will be considered to be outside (or inside) driving lanes. returns: py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes py_trees.common.Status.RUNNING: the rest of the time """ new_status = py_trees.common.Status.RUNNING current_location = CarlaDataProvider.get_location(self.actor) # Get the waypoint at the current location to see if the actor is offroad drive_waypoint = self._map.get_waypoint( current_location, project_to_road=False ) park_waypoint = self._map.get_waypoint( current_location, project_to_road=False, lane_type=carla.LaneType.Parking ) if drive_waypoint or park_waypoint: self._offroad = False else: self._offroad = True # Counts the time offroad if self._offroad: if self._prev_time is None: self._prev_time = GameTime.get_time() else: curr_time = GameTime.get_time() self._time_offroad += curr_time - self._prev_time self._prev_time = curr_time else: self._prev_time = None if self._time_offroad > self._duration: self.test_status = "FAILURE" if self._terminate_on_failure and self.test_status == "FAILURE": new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class EndofRoadTest(Criterion): """ Atomic containing a test to detect when an actor has changed to a different road Args: actor (carla.Actor): CARLA actor to be used for this test duration (float): Time spent after ending the road before the atomic fails. If terminate_on_failure isn't active, this is ignored. optional (bool): If True, the result is not considered for an overall pass/fail result when using the output argument terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met. """ def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name="EndofRoadTest"): """ Setup of the variables """ super(EndofRoadTest, self).__init__(name, actor, 0, None, optional, terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._map = CarlaDataProvider.get_map() self._end_of_road = False self._duration = duration self._start_time = None self._time_end_road = 0 self._road_id = None def update(self): """ First, transforms the actor's current position to its corresponding waypoint. Then the road id is compared with the initial one and if that's the case, a time is started returns: py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes py_trees.common.Status.RUNNING: the rest of the time """ new_status = py_trees.common.Status.RUNNING current_location = CarlaDataProvider.get_location(self.actor) current_waypoint = self._map.get_waypoint(current_location) # Get the current road id if self._road_id is None: self._road_id = current_waypoint.road_id else: # Wait until the actor has left the road if self._road_id != current_waypoint.road_id or self._start_time: # Start counting if self._start_time is None: self._start_time = GameTime.get_time() return new_status curr_time = GameTime.get_time() self._time_end_road = curr_time - self._start_time if self._time_end_road > self._duration: self.test_status = "FAILURE" self.actual_value += 1 return py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class OnSidewalkTest(Criterion): """ Atomic containing a test to detect sidewalk invasions of a specific actor. This atomic can fail when actor has spent a specific time outside driving lanes (defined by OpenDRIVE). Args: actor (carla.Actor): CARLA actor to be used for this test duration (float): Time spent at sidewalks before the atomic fails. If terminate_on_failure isn't active, this is ignored. optional (bool): If True, the result is not considered for an overall pass/fail result when using the output argument terminate_on_failure (bool): If True, the atomic will fail when the duration condition has been met. """ def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False, name="OnSidewalkTest"): """ Construction with sensor setup """ super(OnSidewalkTest, self).__init__(name, actor, 0, None, optional, terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._map = CarlaDataProvider.get_map() self._onsidewalk_active = False self._outside_lane_active = False self._actor_location = self._actor.get_location() self._wrong_sidewalk_distance = 0 self._wrong_outside_lane_distance = 0 self._sidewalk_start_location = None self._outside_lane_start_location = None self._duration = duration self._prev_time = None self._time_outside_lanes = 0 def update(self): """ First, transforms the actor's current position as well as its four corners to their corresponding waypoints. Depending on their lane type, the actor will be considered to be outside (or inside) driving lanes. returns: py_trees.common.Status.FAILURE: when the actor has spent a given duration outside driving lanes and terminate_on_failure is active py_trees.common.Status.RUNNING: the rest of the time """ new_status = py_trees.common.Status.RUNNING if self._terminate_on_failure and self.test_status == "FAILURE": new_status = py_trees.common.Status.FAILURE # Some of the vehicle parameters current_tra = CarlaDataProvider.get_transform(self._actor) current_loc = current_tra.location current_wp = self._map.get_waypoint(current_loc, lane_type=carla.LaneType.Any) # Case 1) Car center is at a sidewalk if current_wp.lane_type == carla.LaneType.Sidewalk: if not self._onsidewalk_active: self._onsidewalk_active = True self._sidewalk_start_location = current_loc # Case 2) Not inside allowed zones (Driving and Parking) elif current_wp.lane_type != carla.LaneType.Driving \ and current_wp.lane_type != carla.LaneType.Parking: # Get the vertices of the vehicle heading_vec = current_tra.get_forward_vector() heading_vec.z = 0 heading_vec = heading_vec / math.sqrt(math.pow(heading_vec.x, 2) + math.pow(heading_vec.y, 2)) perpendicular_vec = carla.Vector3D(-heading_vec.y, heading_vec.x, 0) extent = self.actor.bounding_box.extent x_boundary_vector = heading_vec * extent.x y_boundary_vector = perpendicular_vec * extent.y bbox = [ current_loc + carla.Location(x_boundary_vector - y_boundary_vector), current_loc + carla.Location(x_boundary_vector + y_boundary_vector), current_loc + carla.Location(-1 * x_boundary_vector - y_boundary_vector), current_loc + carla.Location(-1 * x_boundary_vector + y_boundary_vector)] bbox_wp = [ self._map.get_waypoint(bbox[0], lane_type=carla.LaneType.Any), self._map.get_waypoint(bbox[1], lane_type=carla.LaneType.Any), self._map.get_waypoint(bbox[2], lane_type=carla.LaneType.Any), self._map.get_waypoint(bbox[3], lane_type=carla.LaneType.Any)] # Case 2.1) Not quite outside yet if bbox_wp[0].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \ or bbox_wp[1].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \ or bbox_wp[2].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking) \ or bbox_wp[3].lane_type == (carla.LaneType.Driving or carla.LaneType.Parking): self._onsidewalk_active = False self._outside_lane_active = False # Case 2.2) At the mini Shoulders between Driving and Sidewalk elif bbox_wp[0].lane_type == carla.LaneType.Sidewalk \ or bbox_wp[1].lane_type == carla.LaneType.Sidewalk \ or bbox_wp[2].lane_type == carla.LaneType.Sidewalk \ or bbox_wp[3].lane_type == carla.LaneType.Sidewalk: if not self._onsidewalk_active: self._onsidewalk_active = True self._sidewalk_start_location = current_loc else: distance_vehicle_wp = current_loc.distance(current_wp.transform.location) # Case 2.3) Outside lane if distance_vehicle_wp >= current_wp.lane_width / 2: if not self._outside_lane_active: self._outside_lane_active = True self._outside_lane_start_location = current_loc # Case 2.4) Very very edge case (but still inside driving lanes) else: self._onsidewalk_active = False self._outside_lane_active = False # Case 3) Driving and Parking conditions else: # Check for false positives at junctions if current_wp.is_junction: distance_vehicle_wp = math.sqrt( math.pow(current_wp.transform.location.x - current_loc.x, 2) + math.pow(current_wp.transform.location.y - current_loc.y, 2)) if distance_vehicle_wp <= current_wp.lane_width / 2: self._onsidewalk_active = False self._outside_lane_active = False # Else, do nothing, the waypoint is too far to consider it a correct position else: self._onsidewalk_active = False self._outside_lane_active = False # Counts the time offroad if self._onsidewalk_active or self._outside_lane_active: if self._prev_time is None: self._prev_time = GameTime.get_time() else: curr_time = GameTime.get_time() self._time_outside_lanes += curr_time - self._prev_time self._prev_time = curr_time else: self._prev_time = None if self._time_outside_lanes > self._duration: self.test_status = "FAILURE" # Update the distances distance_vector = CarlaDataProvider.get_location(self._actor) - self._actor_location distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2)) if distance >= 0.02: # Used to avoid micro-changes adding to considerable sums self._actor_location = CarlaDataProvider.get_location(self._actor) if self._onsidewalk_active: self._wrong_sidewalk_distance += distance elif self._outside_lane_active: # Only add if car is outside the lane but ISN'T in a junction self._wrong_outside_lane_distance += distance # Register the sidewalk event if not self._onsidewalk_active and self._wrong_sidewalk_distance > 0: self.actual_value += 1 onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION) self._set_event_message( onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance) self._set_event_dict( onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance) self._onsidewalk_active = False self._wrong_sidewalk_distance = 0 self.list_traffic_events.append(onsidewalk_event) # Register the outside of a lane event if not self._outside_lane_active and self._wrong_outside_lane_distance > 0: self.actual_value += 1 outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION) self._set_event_message( outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance) self._set_event_dict( outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance) self._outside_lane_active = False self._wrong_outside_lane_distance = 0 self.list_traffic_events.append(outsidelane_event) self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ If there is currently an event running, it is registered """ # If currently at a sidewalk, register the event if self._onsidewalk_active: self.actual_value += 1 onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION) self._set_event_message( onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance) self._set_event_dict( onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance) self._onsidewalk_active = False self._wrong_sidewalk_distance = 0 self.list_traffic_events.append(onsidewalk_event) # If currently outside of our lane, register the event if self._outside_lane_active: self.actual_value += 1 outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION) self._set_event_message( outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance) self._set_event_dict( outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance) self._outside_lane_active = False self._wrong_outside_lane_distance = 0 self.list_traffic_events.append(outsidelane_event) super(OnSidewalkTest, self).terminate(new_status) def _set_event_message(self, event, location, distance): """ Sets the message of the event """ if event.get_type() == TrafficEventType.ON_SIDEWALK_INFRACTION: message_start = 'Agent invaded the sidewalk' else: message_start = 'Agent went outside the lane' event.set_message( '{} for about {} meters, starting at (x={}, y={}, z={}, t={})'.format( message_start, round(distance, 3), round(location.x, 3), round(location.y, 3), round(location.z, 3), CarlaDataProvider.get_time_step())) def _set_event_dict(self, event, location, distance): """ Sets the dictionary of the event """ event.set_dict({ 'x': location.x, 'y': location.y, 'z': location.z, 'distance': distance}) class OutsideRouteLanesTest(Criterion): """ Atomic to detect if the vehicle is either on a sidewalk or at a wrong lane. The distance spent outside is computed and it is returned as a percentage of the route distance traveled. Args: actor (carla.ACtor): CARLA actor to be used for this test route (list [carla.Location, connection]): series of locations representing the route waypoints optional (bool): If True, the result is not considered for an overall pass/fail result """ ALLOWED_OUT_DISTANCE = 1.3 # At least 0.5, due to the mini-shoulder between lanes and sidewalks MAX_ALLOWED_VEHICLE_ANGLE = 120.0 # Maximum angle between the yaw and waypoint lane MAX_ALLOWED_WAYPOINT_ANGLE = 150.0 # Maximum change between the yaw-lane angle between frames WINDOWS_SIZE = 3 # Amount of additional waypoints checked (in case the first on fails) def __init__(self, actor, route, optional=False, name="OutsideRouteLanesTest"): """ Constructor """ super(OutsideRouteLanesTest, self).__init__(name, actor, 0, None, optional) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._route = route self._current_index = 0 self._route_length = len(self._route) self._waypoints, _ = zip(*self._route) self._map = CarlaDataProvider.get_map() self._pre_ego_waypoint = self._map.get_waypoint(self._actor.get_location()) self._outside_lane_active = False self._wrong_lane_active = False self._last_road_id = None self._last_lane_id = None self._total_distance = 0 self._wrong_distance = 0 def update(self): """ Transforms the actor location and its four corners to waypoints. Depending on its types, the actor will be considered to be at driving lanes, sidewalk or offroad. returns: py_trees.common.Status.FAILURE: when the actor has left driving and terminate_on_failure is active py_trees.common.Status.RUNNING: the rest of the time """ new_status = py_trees.common.Status.RUNNING if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE # Some of the vehicle parameters location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status # 1) Check if outside route lanes self._is_outside_driving_lanes(location) self._is_at_wrong_lane(location) if self._outside_lane_active or self._wrong_lane_active: self.test_status = "FAILURE" # 2) Get the traveled distance for index in range(self._current_index + 1, min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)): # Get the dot product to know if it has passed this location index_location = self._waypoints[index] index_waypoint = self._map.get_waypoint(index_location) wp_dir = index_waypoint.transform.get_forward_vector() # Waypoint's forward vector wp_veh = location - index_location # vector waypoint - vehicle dot_ve_wp = wp_veh.x * wp_dir.x + wp_veh.y * wp_dir.y + wp_veh.z * wp_dir.z if dot_ve_wp > 0: # Get the distance traveled index_location = self._waypoints[index] current_index_location = self._waypoints[self._current_index] new_dist = current_index_location.distance(index_location) # Add it to the total distance self._current_index = index self._total_distance += new_dist # And to the wrong one if outside route lanes if self._outside_lane_active or self._wrong_lane_active: self._wrong_distance += new_dist self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def _is_outside_driving_lanes(self, location): """ Detects if the ego_vehicle is outside driving lanes """ current_driving_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving, project_to_road=True) current_parking_wp = self._map.get_waypoint(location, lane_type=carla.LaneType.Parking, project_to_road=True) driving_distance = location.distance(current_driving_wp.transform.location) if current_parking_wp is not None: # Some towns have no parking parking_distance = location.distance(current_parking_wp.transform.location) else: parking_distance = float('inf') if driving_distance >= parking_distance: distance = parking_distance lane_width = current_parking_wp.lane_width else: distance = driving_distance lane_width = current_driving_wp.lane_width self._outside_lane_active = bool(distance > (lane_width / 2 + self.ALLOWED_OUT_DISTANCE)) def _is_at_wrong_lane(self, location): """ Detects if the ego_vehicle has invaded a wrong lane """ current_waypoint = self._map.get_waypoint(location, lane_type=carla.LaneType.Driving, project_to_road=True) current_lane_id = current_waypoint.lane_id current_road_id = current_waypoint.road_id # Lanes and roads are too chaotic at junctions if current_waypoint.is_junction: self._wrong_lane_active = False elif self._last_road_id != current_road_id or self._last_lane_id != current_lane_id: # Route direction can be considered continuous, except after exiting a junction. if self._pre_ego_waypoint.is_junction: yaw_waypt = current_waypoint.transform.rotation.yaw % 360 yaw_actor = self._actor.get_transform().rotation.yaw % 360 vehicle_lane_angle = (yaw_waypt - yaw_actor) % 360 if vehicle_lane_angle < self.MAX_ALLOWED_VEHICLE_ANGLE \ or vehicle_lane_angle > (360 - self.MAX_ALLOWED_VEHICLE_ANGLE): self._wrong_lane_active = False else: self._wrong_lane_active = True else: # Check for a big gap in waypoint directions. yaw_pre_wp = self._pre_ego_waypoint.transform.rotation.yaw % 360 yaw_cur_wp = current_waypoint.transform.rotation.yaw % 360 waypoint_angle = (yaw_pre_wp - yaw_cur_wp) % 360 if waypoint_angle >= self.MAX_ALLOWED_WAYPOINT_ANGLE \ and waypoint_angle <= (360 - self.MAX_ALLOWED_WAYPOINT_ANGLE): # Is the ego vehicle going back to the lane, or going out? Take the opposite self._wrong_lane_active = not bool(self._wrong_lane_active) else: # Changing to a lane with the same direction self._wrong_lane_active = False # Remember the last state self._last_lane_id = current_lane_id self._last_road_id = current_road_id self._pre_ego_waypoint = current_waypoint def terminate(self, new_status): """ If there is currently an event running, it is registered """ if self._wrong_distance > 0: percentage = self._wrong_distance / self._total_distance * 100 outside_lane = TrafficEvent(event_type=TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION) outside_lane.set_message( "Agent went outside its route lanes for about {} meters " "({}% of the completed route, t={})".format( round(self._wrong_distance, 3), round(percentage, 2), CarlaDataProvider.get_time_step())) outside_lane.set_dict({ 'distance': self._wrong_distance, 'percentage': percentage }) self._wrong_distance = 0 self.list_traffic_events.append(outside_lane) self.actual_value = round(percentage, 2) super(OutsideRouteLanesTest, self).terminate(new_status) class WrongLaneTest(Criterion): """ This class contains an atomic test to detect invasions to wrong direction lanes. Important parameters: - actor: CARLA actor to be used for this test - optional [optional]: If True, the result is not considered for an overall pass/fail result """ MAX_ALLOWED_ANGLE = 120.0 MAX_ALLOWED_WAYPOINT_ANGLE = 150.0 def __init__(self, actor, optional=False, name="WrongLaneTest"): """ Construction with sensor setup """ super(WrongLaneTest, self).__init__(name, actor, 0, None, optional) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._map = CarlaDataProvider.get_map() self._last_lane_id = None self._last_road_id = None self._in_lane = True self._wrong_distance = 0 self._actor_location = self._actor.get_location() self._previous_lane_waypoint = self._map.get_waypoint(self._actor.get_location()) self._wrong_lane_start_location = None def update(self): """ Check lane invasion count """ new_status = py_trees.common.Status.RUNNING if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE lane_waypoint = self._map.get_waypoint(self._actor.get_location()) current_lane_id = lane_waypoint.lane_id current_road_id = lane_waypoint.road_id if (self._last_road_id != current_road_id or self._last_lane_id != current_lane_id) \ and not lane_waypoint.is_junction: next_waypoint = lane_waypoint.next(2.0)[0] if not next_waypoint: return new_status # The waypoint route direction can be considered continuous. # Therefore just check for a big gap in waypoint directions. previous_lane_direction = self._previous_lane_waypoint.transform.get_forward_vector() current_lane_direction = lane_waypoint.transform.get_forward_vector() p_lane_vector = np.array([previous_lane_direction.x, previous_lane_direction.y]) c_lane_vector = np.array([current_lane_direction.x, current_lane_direction.y]) waypoint_angle = math.degrees( math.acos(np.clip(np.dot(p_lane_vector, c_lane_vector) / (np.linalg.norm(p_lane_vector) * np.linalg.norm(c_lane_vector)), -1.0, 1.0))) if waypoint_angle > self.MAX_ALLOWED_WAYPOINT_ANGLE and self._in_lane: self.test_status = "FAILURE" self._in_lane = False self.actual_value += 1 self._wrong_lane_start_location = self._actor_location else: # Reset variables self._in_lane = True # Continuity is broken after a junction so check vehicle-lane angle instead if self._previous_lane_waypoint.is_junction: vector_wp = np.array([next_waypoint.transform.location.x - lane_waypoint.transform.location.x, next_waypoint.transform.location.y - lane_waypoint.transform.location.y]) vector_actor = np.array([math.cos(math.radians(self._actor.get_transform().rotation.yaw)), math.sin(math.radians(self._actor.get_transform().rotation.yaw))]) vehicle_lane_angle = math.degrees( math.acos(np.clip(np.dot(vector_actor, vector_wp) / (np.linalg.norm(vector_wp)), -1.0, 1.0))) if vehicle_lane_angle > self.MAX_ALLOWED_ANGLE: self.test_status = "FAILURE" self._in_lane = False self.actual_value += 1 self._wrong_lane_start_location = self._actor.get_location() # Keep adding "meters" to the counter distance_vector = self._actor.get_location() - self._actor_location distance = math.sqrt(math.pow(distance_vector.x, 2) + math.pow(distance_vector.y, 2)) if distance >= 0.02: # Used to avoid micro-changes adding add to considerable sums self._actor_location = CarlaDataProvider.get_location(self._actor) if not self._in_lane and not lane_waypoint.is_junction: self._wrong_distance += distance # Register the event if self._in_lane and self._wrong_distance > 0: wrong_way_event = TrafficEvent(event_type=TrafficEventType.WRONG_WAY_INFRACTION) self._set_event_message(wrong_way_event, self._wrong_lane_start_location, self._wrong_distance, current_road_id, current_lane_id) self._set_event_dict(wrong_way_event, self._wrong_lane_start_location, self._wrong_distance, current_road_id, current_lane_id) self.list_traffic_events.append(wrong_way_event) self._wrong_distance = 0 # Remember the last state self._last_lane_id = current_lane_id self._last_road_id = current_road_id self._previous_lane_waypoint = lane_waypoint self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ If there is currently an event running, it is registered """ if not self._in_lane: lane_waypoint = self._map.get_waypoint(self._actor.get_location()) current_lane_id = lane_waypoint.lane_id current_road_id = lane_waypoint.road_id wrong_way_event = TrafficEvent(event_type=TrafficEventType.WRONG_WAY_INFRACTION) self._set_event_message(wrong_way_event, self._wrong_lane_start_location, self._wrong_distance, current_road_id, current_lane_id) self._set_event_dict(wrong_way_event, self._wrong_lane_start_location, self._wrong_distance, current_road_id, current_lane_id) self._wrong_distance = 0 self._in_lane = True self.list_traffic_events.append(wrong_way_event) super(WrongLaneTest, self).terminate(new_status) def _set_event_message(self, event, location, distance, road_id, lane_id): """ Sets the message of the event """ event.set_message( "Agent invaded a lane in opposite direction for {} meters, starting at (x={}, y={}, z={}, t={}). " "road_id={}, lane_id={}".format( round(distance, 3), round(location.x, 3), round(location.y, 3), round(location.z, 3), CarlaDataProvider.get_time_step(), road_id, lane_id)) def _set_event_dict(self, event, location, distance, road_id, lane_id): """ Sets the dictionary of the event """ event.set_dict({ 'x': location.x, 'y': location.y, 'z': location.y, 'distance': distance, 'road_id': road_id, 'lane_id': lane_id}) class InRadiusRegionTest(Criterion): """ The test is a success if the actor is within a given radius of a specified region Important parameters: - actor: CARLA actor to be used for this test - x, y, radius: Position (x,y) and radius (in meters) used to get the checked region """ def __init__(self, actor, x, y, radius, name="InRadiusRegionTest"): """ """ super(InRadiusRegionTest, self).__init__(name, actor, 0) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._x = x # pylint: disable=invalid-name self._y = y # pylint: disable=invalid-name self._radius = radius def update(self): """ Check if the actor location is within trigger region """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status if self.test_status != "SUCCESS": in_radius = math.sqrt(((location.x - self._x)**2) + ((location.y - self._y)**2)) < self._radius if in_radius: route_completion_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETED) route_completion_event.set_message("Destination was successfully reached") self.list_traffic_events.append(route_completion_event) self.test_status = "SUCCESS" else: self.test_status = "RUNNING" if self.test_status == "SUCCESS": new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InRouteTest(Criterion): """ The test is a success if the actor is never outside route. The actor can go outside of the route but only for a certain amount of distance Important parameters: - actor: CARLA actor to be used for this test - route: Route to be checked - offroad_max: Maximum distance (in meters) the actor can deviate from the route - offroad_min: Maximum safe distance (in meters). Might eventually cause failure - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ MAX_ROUTE_PERCENTAGE = 30 # % WINDOWS_SIZE = 5 # Amount of additional waypoints checked def __init__(self, actor, route, offroad_min=-1, offroad_max=30, name="InRouteTest", terminate_on_failure=False): """ """ super(InRouteTest, self).__init__(name, actor, 0, terminate_on_failure=terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._route = route self._offroad_max = offroad_max # Unless specified, halve of the max value if offroad_min == -1: self._offroad_min = self._offroad_max / 2 else: self._offroad_min = self._offroad_min self._world = CarlaDataProvider.get_world() self._waypoints, _ = zip(*self._route) self._route_length = len(self._route) self._current_index = 0 self._out_route_distance = 0 self._in_safe_route = True self._accum_meters = [] prev_wp = self._waypoints[0] for i, wp in enumerate(self._waypoints): d = wp.distance(prev_wp) if i > 0: accum = self._accum_meters[i - 1] else: accum = 0 self._accum_meters.append(d + accum) prev_wp = wp # Blackboard variable blackv = py_trees.blackboard.Blackboard() _ = blackv.set("InRoute", True) def update(self): """ Check if the actor location is within trigger region """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE elif self.test_status == "RUNNING" or self.test_status == "INIT": off_route = True shortest_distance = float('inf') closest_index = -1 # Get the closest distance for index in range(self._current_index, min(self._current_index + self.WINDOWS_SIZE + 1, self._route_length)): ref_waypoint = self._waypoints[index] distance = math.sqrt(((location.x - ref_waypoint.x) ** 2) + ((location.y - ref_waypoint.y) ** 2)) if distance <= shortest_distance: closest_index = index shortest_distance = distance if closest_index == -1 or shortest_distance == float('inf'): return new_status # Check if the actor is out of route if shortest_distance < self._offroad_max: off_route = False self._in_safe_route = bool(shortest_distance < self._offroad_min) # If actor advanced a step, record the distance if self._current_index != closest_index: new_dist = self._accum_meters[closest_index] - self._accum_meters[self._current_index] # If too far from the route, add it and check if its value if not self._in_safe_route: self._out_route_distance += new_dist out_route_percentage = 100 * self._out_route_distance / self._accum_meters[-1] if out_route_percentage > self.MAX_ROUTE_PERCENTAGE: off_route = True self._current_index = closest_index if off_route: # Blackboard variable blackv = py_trees.blackboard.Blackboard() _ = blackv.set("InRoute", False) route_deviation_event = TrafficEvent(event_type=TrafficEventType.ROUTE_DEVIATION) route_deviation_event.set_message( "Agent deviated from the route at (x={}, y={}, z={}, t={})".format( round(location.x, 3), round(location.y, 3), round(location.z, 3), CarlaDataProvider.get_time_step())) route_deviation_event.set_dict({ 'x': location.x, 'y': location.y, 'z': location.z}) self.list_traffic_events.append(route_deviation_event) self.test_status = "FAILURE" self.actual_value += 1 new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class RouteCompletionTest(Criterion): """ Check at which stage of the route is the actor at each tick Important parameters: - actor: CARLA actor to be used for this test - route: Route to be checked - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ DISTANCE_THRESHOLD = 10.0 # meters WINDOWS_SIZE = 2 def __init__(self, actor, route, name="RouteCompletionTest", terminate_on_failure=False): """ """ super(RouteCompletionTest, self).__init__(name, actor, 100, terminate_on_failure=terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._route = route self._map = CarlaDataProvider.get_map() self._wsize = self.WINDOWS_SIZE self._current_index = 0 self._route_length = len(self._route) self._waypoints, _ = zip(*self._route) self.target = self._waypoints[-1] self._accum_meters = [] prev_wp = self._waypoints[0] for i, wp in enumerate(self._waypoints): d = wp.distance(prev_wp) if i > 0: accum = self._accum_meters[i - 1] else: accum = 0 self._accum_meters.append(d + accum) prev_wp = wp self._traffic_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETION) self.list_traffic_events.append(self._traffic_event) self._percentage_route_completed = 0.0 def update(self): """ Check if the actor location is within trigger region """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE elif self.test_status == "RUNNING" or self.test_status == "INIT": for index in range(self._current_index, min(self._current_index + self._wsize + 1, self._route_length)): # Get the dot product to know if it has passed this location ref_waypoint = self._waypoints[index] wp = self._map.get_waypoint(ref_waypoint) wp_dir = wp.transform.get_forward_vector() # Waypoint's forward vector wp_veh = location - ref_waypoint # vector waypoint - vehicle dot_ve_wp = wp_veh.x * wp_dir.x + wp_veh.y * wp_dir.y + wp_veh.z * wp_dir.z if dot_ve_wp > 0: # good! segment completed! self._current_index = index self._percentage_route_completed = 100.0 * float(self._accum_meters[self._current_index]) \ / float(self._accum_meters[-1]) self._traffic_event.set_dict({ 'route_completed': self._percentage_route_completed}) self._traffic_event.set_message( "Agent has completed > {:.2f}% of the route".format( self._percentage_route_completed)) if self._percentage_route_completed > 99.0 and location.distance(self.target) < self.DISTANCE_THRESHOLD: route_completion_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETED) route_completion_event.set_message("Destination was successfully reached") self.list_traffic_events.append(route_completion_event) self.test_status = "SUCCESS" self._percentage_route_completed = 100 elif self.test_status == "SUCCESS": new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def terminate(self, new_status): """ Set test status to failure if not successful and terminate """ self.actual_value = round(self._percentage_route_completed, 2) if self.test_status == "INIT": self.test_status = "FAILURE" super(RouteCompletionTest, self).terminate(new_status) class RunningRedLightTest(Criterion): """ Check if an actor is running a red light Important parameters: - actor: CARLA actor to be used for this test - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ DISTANCE_LIGHT = 15 # m def __init__(self, actor, name="RunningRedLightTest", terminate_on_failure=False): """ Init """ super(RunningRedLightTest, self).__init__(name, actor, 0, terminate_on_failure=terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._world = actor.get_world() self._map = CarlaDataProvider.get_map() self._list_traffic_lights = [] self._last_red_light_id = None self.actual_value = 0 self.debug = False all_actors = self._world.get_actors() for _actor in all_actors: if 'traffic_light' in _actor.type_id: center, waypoints = self.get_traffic_light_waypoints(_actor) self._list_traffic_lights.append((_actor, center, waypoints)) # pylint: disable=no-self-use def is_vehicle_crossing_line(self, seg1, seg2): """ check if vehicle crosses a line segment """ line1 = shapely.geometry.LineString([(seg1[0].x, seg1[0].y), (seg1[1].x, seg1[1].y)]) line2 = shapely.geometry.LineString([(seg2[0].x, seg2[0].y), (seg2[1].x, seg2[1].y)]) inter = line1.intersection(line2) return not inter.is_empty def update(self): """ Check if the actor is running a red light """ new_status = py_trees.common.Status.RUNNING transform = CarlaDataProvider.get_transform(self._actor) location = transform.location if location is None: return new_status veh_extent = self._actor.bounding_box.extent.x tail_close_pt = self.rotate_point(carla.Vector3D(-0.8 * veh_extent, 0.0, location.z), transform.rotation.yaw) tail_close_pt = location + carla.Location(tail_close_pt) tail_far_pt = self.rotate_point(carla.Vector3D(-veh_extent - 1, 0.0, location.z), transform.rotation.yaw) tail_far_pt = location + carla.Location(tail_far_pt) for traffic_light, center, waypoints in self._list_traffic_lights: if self.debug: z = 2.1 if traffic_light.state == carla.TrafficLightState.Red: color = carla.Color(155, 0, 0) elif traffic_light.state == carla.TrafficLightState.Green: color = carla.Color(0, 155, 0) else: color = carla.Color(155, 155, 0) self._world.debug.draw_point(center + carla.Location(z=z), size=0.2, color=color, life_time=0.01) for wp in waypoints: text = "{}.{}".format(wp.road_id, wp.lane_id) self._world.debug.draw_string( wp.transform.location + carla.Location(x=1, z=z), text, color=color, life_time=0.01) self._world.debug.draw_point( wp.transform.location + carla.Location(z=z), size=0.1, color=color, life_time=0.01) center_loc = carla.Location(center) if self._last_red_light_id and self._last_red_light_id == traffic_light.id: continue if center_loc.distance(location) > self.DISTANCE_LIGHT: continue if traffic_light.state != carla.TrafficLightState.Red: continue for wp in waypoints: tail_wp = self._map.get_waypoint(tail_far_pt) # Calculate the dot product (Might be unscaled, as only its sign is important) ve_dir = CarlaDataProvider.get_transform(self._actor).get_forward_vector() wp_dir = wp.transform.get_forward_vector() dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z # Check the lane until all the "tail" has passed if tail_wp.road_id == wp.road_id and tail_wp.lane_id == wp.lane_id and dot_ve_wp > 0: # This light is red and is affecting our lane yaw_wp = wp.transform.rotation.yaw lane_width = wp.lane_width location_wp = wp.transform.location lft_lane_wp = self.rotate_point(carla.Vector3D(0.4 * lane_width, 0.0, location_wp.z), yaw_wp + 90) lft_lane_wp = location_wp + carla.Location(lft_lane_wp) rgt_lane_wp = self.rotate_point(carla.Vector3D(0.4 * lane_width, 0.0, location_wp.z), yaw_wp - 90) rgt_lane_wp = location_wp + carla.Location(rgt_lane_wp) # Is the vehicle traversing the stop line? if self.is_vehicle_crossing_line((tail_close_pt, tail_far_pt), (lft_lane_wp, rgt_lane_wp)): self.test_status = "FAILURE" self.actual_value += 1 location = traffic_light.get_transform().location red_light_event = TrafficEvent(event_type=TrafficEventType.TRAFFIC_LIGHT_INFRACTION) red_light_event.set_message( "Agent ran a red light {} at (x={}, y={}, z={}, t={})".format( traffic_light.id, round(location.x, 3), round(location.y, 3), round(location.z, 3), CarlaDataProvider.get_time_step())) red_light_event.set_dict({ 'id': traffic_light.id, 'x': location.x, 'y': location.y, 'z': location.z}) self.list_traffic_events.append(red_light_event) self._last_red_light_id = traffic_light.id break if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status def rotate_point(self, 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) def get_traffic_light_waypoints(self, traffic_light): """ get area of a given traffic light """ base_transform = traffic_light.get_transform() base_rot = base_transform.rotation.yaw area_loc = base_transform.transform(traffic_light.trigger_volume.location) # Discretize the trigger box into points area_ext = traffic_light.trigger_volume.extent x_values = np.arange(-0.9 * area_ext.x, 0.9 * area_ext.x, 1.0) # 0.9 to avoid crossing to adjacent lanes area = [] for x in x_values: point = self.rotate_point(carla.Vector3D(x, 0, area_ext.z), base_rot) point_location = area_loc + carla.Location(x=point.x, y=point.y) area.append(point_location) # Get the waypoints of these points, removing duplicates ini_wps = [] for pt in area: wpx = self._map.get_waypoint(pt) # As x_values are arranged in order, only the last one has to be checked if not ini_wps or ini_wps[-1].road_id != wpx.road_id or ini_wps[-1].lane_id != wpx.lane_id: ini_wps.append(wpx) # Advance them until the intersection wps = [] for wpx in ini_wps: while not wpx.is_intersection: next_wp = wpx.next(0.5)[0] if next_wp and not next_wp.is_intersection: wpx = next_wp else: break wps.append(wpx) return area_loc, wps class RunningStopTest(Criterion): """ Check if an actor is running a stop sign Important parameters: - actor: CARLA actor to be used for this test - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ PROXIMITY_THRESHOLD = 50.0 # meters SPEED_THRESHOLD = 0.1 WAYPOINT_STEP = 1.0 # meters def __init__(self, actor, name="RunningStopTest", terminate_on_failure=False): """ """ super(RunningStopTest, self).__init__(name, actor, 0, terminate_on_failure=terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map() self._list_stop_signs = [] self._target_stop_sign = None self._stop_completed = False self._affected_by_stop = False self.actual_value = 0 all_actors = self._world.get_actors() for _actor in all_actors: if 'traffic.stop' in _actor.type_id: self._list_stop_signs.append(_actor) @staticmethod def point_inside_boundingbox(point, bb_center, bb_extent): """ X :param point: :param bb_center: :param bb_extent: :return: """ # pylint: disable=invalid-name A = carla.Vector2D(bb_center.x - bb_extent.x, bb_center.y - bb_extent.y) B = carla.Vector2D(bb_center.x + bb_extent.x, bb_center.y - bb_extent.y) D = carla.Vector2D(bb_center.x - bb_extent.x, bb_center.y + bb_extent.y) M = carla.Vector2D(point.x, point.y) AB = B - A AD = D - A AM = M - A am_ab = AM.x * AB.x + AM.y * AB.y ab_ab = AB.x * AB.x + AB.y * AB.y am_ad = AM.x * AD.x + AM.y * AD.y ad_ad = AD.x * AD.x + AD.y * AD.y return am_ab > 0 and am_ab < ab_ab and am_ad > 0 and am_ad < ad_ad def is_actor_affected_by_stop(self, actor, stop, multi_step=20): """ Check if the given actor is affected by the stop """ affected = False # first we run a fast coarse test current_location = actor.get_location() stop_location = stop.get_transform().location if stop_location.distance(current_location) > self.PROXIMITY_THRESHOLD: return affected stop_t = stop.get_transform() transformed_tv = stop_t.transform(stop.trigger_volume.location) # slower and accurate test based on waypoint's horizon and geometric test list_locations = [current_location] waypoint = self._map.get_waypoint(current_location) for _ in range(multi_step): if waypoint: next_wps = waypoint.next(self.WAYPOINT_STEP) if not next_wps: break waypoint = next_wps[0] if not waypoint: break list_locations.append(waypoint.transform.location) for actor_location in list_locations: if self.point_inside_boundingbox(actor_location, transformed_tv, stop.trigger_volume.extent): affected = True return affected def _scan_for_stop_sign(self): target_stop_sign = None ve_tra = CarlaDataProvider.get_transform(self._actor) ve_dir = ve_tra.get_forward_vector() wp = self._map.get_waypoint(ve_tra.location) wp_dir = wp.transform.get_forward_vector() dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z if dot_ve_wp > 0: # Ignore all when going in a wrong lane for stop_sign in self._list_stop_signs: if self.is_actor_affected_by_stop(self._actor, stop_sign): # this stop sign is affecting the vehicle target_stop_sign = stop_sign break return target_stop_sign def update(self): """ Check if the actor is running a red light """ new_status = py_trees.common.Status.RUNNING location = self._actor.get_location() if location is None: return new_status if not self._target_stop_sign: # scan for stop signs self._target_stop_sign = self._scan_for_stop_sign() else: # we were in the middle of dealing with a stop sign if not self._stop_completed: # did the ego-vehicle stop? current_speed = CarlaDataProvider.get_velocity(self._actor) if current_speed < self.SPEED_THRESHOLD: self._stop_completed = True if not self._affected_by_stop: stop_location = self._target_stop_sign.get_location() stop_extent = self._target_stop_sign.trigger_volume.extent if self.point_inside_boundingbox(location, stop_location, stop_extent): self._affected_by_stop = True if not self.is_actor_affected_by_stop(self._actor, self._target_stop_sign): # is the vehicle out of the influence of this stop sign now? if not self._stop_completed and self._affected_by_stop: # did we stop? self.actual_value += 1 self.test_status = "FAILURE" stop_location = self._target_stop_sign.get_transform().location running_stop_event = TrafficEvent(event_type=TrafficEventType.STOP_INFRACTION) running_stop_event.set_message( "Agent ran a stop with id={} at (x={}, y={}, z={}, t={})".format( self._target_stop_sign.id, round(stop_location.x, 3), round(stop_location.y, 3), round(stop_location.z, 3), CarlaDataProvider.get_time_step())) running_stop_event.set_dict({ 'id': self._target_stop_sign.id, 'x': stop_location.x, 'y': stop_location.y, 'z': stop_location.z}) self.list_traffic_events.append(running_stop_event) # reset state self._target_stop_sign = None self._stop_completed = False self._affected_by_stop = False if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status ================================================ FILE: scenario_runner/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py ================================================ #!/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 atomic scenario behaviors that reflect trigger conditions to either activate another behavior, or to stop another behavior. For example, such a condition could be "InTriggerRegion", which checks that a given actor reached a certain region on the map, and then starts/stops a behavior of this actor. The atomics are implemented with py_trees and make use of the AtomicCondition base class """ from __future__ import print_function import operator import datetime import math import py_trees import carla from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO from srunner.scenariomanager.scenarioatomics.atomic_behaviors import calculate_distance from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import GameTime from srunner.tools.scenario_helper import get_distance_along_route import srunner.tools EPSILON = 0.001 class AtomicCondition(py_trees.behaviour.Behaviour): """ Base class for all atomic conditions used to setup a scenario *All behaviors should use this class as parent* Important parameters: - name: Name of the atomic condition """ def __init__(self, name): """ Default init. Has to be called via super from derived class """ super(AtomicCondition, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self.name = name def setup(self, unused_timeout=15): """ Default setup """ self.logger.debug("%s.setup()" % (self.__class__.__name__)) return True def initialise(self): """ Initialise setup """ self.logger.debug("%s.initialise()" % (self.__class__.__name__)) def terminate(self, new_status): """ Default terminate. Can be extended in derived class """ self.logger.debug("%s.terminate()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) class InTriggerDistanceToOSCPosition(AtomicCondition): """ OpenSCENARIO atomic This class contains the trigger condition for a distance to an OpenSCENARIO position Args: actor (carla.Actor): CARLA actor to execute the behavior osc_position (str): OpenSCENARIO position distance (float): Trigger distance between the actor and the target location in meters name (str): Name of the condition The condition terminates with SUCCESS, when the actor reached the target distance to the openSCENARIO position """ def __init__(self, actor, osc_position, distance, along_route=False, comparison_operator=operator.lt, name="InTriggerDistanceToOSCPosition"): """ Setup parameters """ super(InTriggerDistanceToOSCPosition, self).__init__(name) self._actor = actor self._osc_position = osc_position self._distance = distance self._along_route = along_route self._comparison_operator = comparison_operator self._map = CarlaDataProvider.get_map() if self._along_route: # Get the global route planner, used to calculate the route dao = GlobalRoutePlannerDAO(self._map, 0.5) grp = GlobalRoutePlanner(dao) grp.setup() self._grp = grp else: self._grp = None def initialise(self): if self._distance < 0: raise ValueError("distance value must be positive") def update(self): """ Check if actor is in trigger distance """ new_status = py_trees.common.Status.RUNNING # calculate transform with method in openscenario_parser.py osc_transform = srunner.tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform( self._osc_position) if osc_transform is not None: osc_location = osc_transform.location actor_location = CarlaDataProvider.get_location(self._actor) if self._along_route: # Global planner needs a location at a driving lane actor_location = self._map.get_waypoint(actor_location).transform.location osc_location = self._map.get_waypoint(osc_location).transform.location distance = calculate_distance(actor_location, osc_location, self._grp) if self._comparison_operator(distance, self._distance): new_status = py_trees.common.Status.SUCCESS return new_status class InTimeToArrivalToOSCPosition(AtomicCondition): """ OpenSCENARIO atomic This class contains a trigger if an actor arrives within a given time to an OpenSCENARIO position Important parameters: - actor: CARLA actor to execute the behavior - osc_position: OpenSCENARIO position - time: The behavior is successful, if TTA is less than _time_ in seconds - name: Name of the condition The condition terminates with SUCCESS, when the actor can reach the position within the given time """ def __init__(self, actor, osc_position, time, along_route=False, comparison_operator=operator.lt, name="InTimeToArrivalToOSCPosition"): """ Setup parameters """ super(InTimeToArrivalToOSCPosition, self).__init__(name) self._map = CarlaDataProvider.get_map() self._actor = actor self._osc_position = osc_position self._time = float(time) self._along_route = along_route self._comparison_operator = comparison_operator if self._along_route: # Get the global route planner, used to calculate the route dao = GlobalRoutePlannerDAO(self._map, 0.5) grp = GlobalRoutePlanner(dao) grp.setup() self._grp = grp else: self._grp = None def initialise(self): if self._time < 0: raise ValueError("time value must be positive") def update(self): """ Check if actor can arrive within trigger time """ new_status = py_trees.common.Status.RUNNING # calculate transform with method in openscenario_parser.py try: osc_transform = srunner.tools.openscenario_parser.OpenScenarioParser.convert_position_to_transform( self._osc_position) except AttributeError: return py_trees.common.Status.FAILURE target_location = osc_transform.location actor_location = CarlaDataProvider.get_location(self._actor) if target_location is None or actor_location is None: return new_status if self._along_route: # Global planner needs a location at a driving lane actor_location = self._map.get_waypoint(actor_location).transform.location target_location = self._map.get_waypoint(target_location).transform.location distance = calculate_distance(actor_location, target_location, self._grp) actor_velocity = CarlaDataProvider.get_velocity(self._actor) # time to arrival if actor_velocity > 0: time_to_arrival = distance / actor_velocity elif distance == 0: time_to_arrival = 0 else: time_to_arrival = float('inf') if self._comparison_operator(time_to_arrival, self._time): new_status = py_trees.common.Status.SUCCESS return new_status class StandStill(AtomicCondition): """ This class contains a standstill behavior of a scenario Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - duration: Duration of the behavior in seconds The condition terminates with SUCCESS, when the actor does not move """ def __init__(self, actor, name, duration=float("inf")): """ Setup actor """ super(StandStill, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._duration = duration self._start_time = 0 def initialise(self): """ Initialize the start time of this condition """ self._start_time = GameTime.get_time() super(StandStill, self).initialise() def update(self): """ Check if the _actor stands still (v=0) """ new_status = py_trees.common.Status.RUNNING velocity = CarlaDataProvider.get_velocity(self._actor) if velocity > EPSILON: self._start_time = GameTime.get_time() if GameTime.get_time() - self._start_time > self._duration: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class RelativeVelocityToOtherActor(AtomicCondition): """ Atomic containing a comparison between an actor's velocity and another actor's one. The behavior returns SUCCESS when the expected comparison (greater than / less than / equal to) is achieved Args: actor (carla.Actor): actor from which the velocity is taken other_actor (carla.Actor): The actor with the reference velocity speed (float): Difference of speed between the actors name (string): Name of the condition comparison_operator: Type "operator", used to compare the two velocities """ def __init__(self, actor, other_actor, speed, comparison_operator=operator.gt, name="RelativeVelocityToOtherActor"): """ Setup the parameters """ super(RelativeVelocityToOtherActor, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._other_actor = other_actor self._relative_speed = speed self._comparison_operator = comparison_operator def update(self): """ Gets the speed of the two actors and compares them according to the comparison operator returns: py_trees.common.Status.RUNNING when the comparison fails and py_trees.common.Status.SUCCESS when it succeeds """ new_status = py_trees.common.Status.RUNNING curr_speed = CarlaDataProvider.get_velocity(self._actor) other_speed = CarlaDataProvider.get_velocity(self._other_actor) relative_speed = curr_speed - other_speed if self._comparison_operator(relative_speed, self._relative_speed): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class TriggerVelocity(AtomicCondition): """ Atomic containing a comparison between an actor's speed and a reference one. The behavior returns SUCCESS when the expected comparison (greater than / less than / equal to) is achieved. Args: actor (carla.Actor): CARLA actor from which the speed will be taken. name (string): Name of the atomic target_velocity (float): velcoity to be compared with the actor's one comparison_operator: Type "operator", used to compare the two velocities """ def __init__(self, actor, target_velocity, comparison_operator=operator.gt, name="TriggerVelocity"): """ Setup the atomic parameters """ super(TriggerVelocity, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._target_velocity = target_velocity self._comparison_operator = comparison_operator def update(self): """ Gets the speed of the actor and compares it with the reference one returns: py_trees.common.Status.RUNNING when the comparison fails and py_trees.common.Status.SUCCESS when it succeeds """ new_status = py_trees.common.Status.RUNNING actor_speed = CarlaDataProvider.get_velocity(self._actor) if self._comparison_operator(actor_speed, self._target_velocity): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class TriggerAcceleration(AtomicCondition): """ Atomic containing a comparison between an actor's acceleration and a reference one. The behavior returns SUCCESS when the expected comparison (greater than / less than / equal to) is achieved Args: actor (carla.Actor): CARLA actor to execute the behavior name (str): Name of the condition target_acceleration (float): Acceleration reference (in m/s^2) on which the success is dependent comparison_operator (operator): Type "operator", used to compare the two acceleration """ def __init__(self, actor, target_acceleration, comparison_operator=operator.gt, name="TriggerAcceleration"): """ Setup trigger acceleration """ super(TriggerAcceleration, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._target_acceleration = target_acceleration self._comparison_operator = comparison_operator def update(self): """ Gets the accleration of the actor and compares it with the reference one returns: py_trees.common.Status.RUNNING when the comparison fails and py_trees.common.Status.SUCCESS when it succeeds """ new_status = py_trees.common.Status.RUNNING acceleration = self._actor.get_acceleration() linear_accel = math.sqrt(math.pow(acceleration.x, 2) + math.pow(acceleration.y, 2) + math.pow(acceleration.z, 2)) if self._comparison_operator(linear_accel, self._target_acceleration): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class TimeOfDayComparison(AtomicCondition): """ Atomic containing a comparison between the current time of day of the simulation and a given one. The behavior returns SUCCESS when the expected comparison (greater than / less than / equal to) is achieved Args: datetime (datetime): CARLA actor to execute the behavior name (str): Name of the condition target_acceleration (float): Acceleration reference (in m/s^2) on which the success is dependent comparison_operator (operator): Type "operator", used to compare the two acceleration """ def __init__(self, dattime, comparison_operator=operator.gt, name="TimeOfDayComparison"): """ """ super(TimeOfDayComparison, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._datetime = datetime.datetime.strptime(dattime, "%Y-%m-%dT%H:%M:%S") self._comparison_operator = comparison_operator def update(self): """ Gets the time of day of the simulation and compares it with the reference one returns: py_trees.common.Status.RUNNING when the comparison fails and py_trees.common.Status.SUCCESS when it succeeds """ new_status = py_trees.common.Status.RUNNING try: check_dtime = operator.attrgetter("Datetime") dtime = check_dtime(py_trees.blackboard.Blackboard()) except AttributeError: pass if self._comparison_operator(dtime, self._datetime): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class OSCStartEndCondition(AtomicCondition): """ This class contains a check if a named story element has started/terminated. Important parameters: - element_name: The story element's name attribute - element_type: The element type [act,scene,maneuver,event,action] - rule: Either START or END The condition terminates with SUCCESS, when the named story element starts """ def __init__(self, element_type, element_name, rule, name="OSCStartEndCondition"): """ Setup element details """ super(OSCStartEndCondition, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._element_type = element_type.upper() self._element_name = element_name self._rule = rule.upper() self._start_time = None self._blackboard = py_trees.blackboard.Blackboard() def initialise(self): """ Initialize the start time of this condition """ self._start_time = GameTime.get_time() super(OSCStartEndCondition, self).initialise() def update(self): """ Check if the specified story element has started/ended since the beginning of the condition """ new_status = py_trees.common.Status.RUNNING if new_status == py_trees.common.Status.RUNNING: blackboard_variable_name = "({}){}-{}".format(self._element_type, self._element_name, self._rule) element_start_time = self._blackboard.get(blackboard_variable_name) if element_start_time and element_start_time >= self._start_time: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTriggerRegion(AtomicCondition): """ This class contains the trigger region (condition) of a scenario Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - min_x, max_x, min_y, max_y: bounding box of the trigger region The condition terminates with SUCCESS, when the actor reached the target region """ def __init__(self, actor, min_x, max_x, min_y, max_y, name="TriggerRegion"): """ Setup trigger region (rectangle provided by [min_x,min_y] and [max_x,max_y] """ super(InTriggerRegion, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._min_x = min_x self._max_x = max_x self._min_y = min_y self._max_y = max_y def update(self): """ Check if the _actor location is within trigger region """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status not_in_region = (location.x < self._min_x or location.x > self._max_x) or ( location.y < self._min_y or location.y > self._max_y) if not not_in_region: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTriggerDistanceToVehicle(AtomicCondition): """ This class contains the trigger distance (condition) between to actors of a scenario Important parameters: - actor: CARLA actor to execute the behavior - reference_actor: Reference CARLA actor - name: Name of the condition - distance: Trigger distance between the two actors in meters - dx, dy, dz: distance to reference_location (location of reference_actor) The condition terminates with SUCCESS, when the actor reached the target distance to the other actor """ def __init__(self, reference_actor, actor, distance, comparison_operator=operator.lt, name="TriggerDistanceToVehicle"): """ Setup trigger distance """ super(InTriggerDistanceToVehicle, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._reference_actor = reference_actor self._actor = actor self._distance = distance self._comparison_operator = comparison_operator def update(self): """ Check if the ego vehicle is within trigger distance to other actor """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) reference_location = CarlaDataProvider.get_location(self._reference_actor) if location is None or reference_location is None: return new_status if self._comparison_operator(calculate_distance(location, reference_location), self._distance): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTriggerDistanceToLocation(AtomicCondition): """ This class contains the trigger (condition) for a distance to a fixed location of a scenario Important parameters: - actor: CARLA actor to execute the behavior - target_location: Reference location (carla.location) - name: Name of the condition - distance: Trigger distance between the actor and the target location in meters The condition terminates with SUCCESS, when the actor reached the target distance to the given location """ def __init__(self, actor, target_location, distance, comparison_operator=operator.lt, name="InTriggerDistanceToLocation"): """ Setup trigger distance """ super(InTriggerDistanceToLocation, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._target_location = target_location self._actor = actor self._distance = distance self._comparison_operator = comparison_operator def update(self): """ Check if the actor is within trigger distance to the target location """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) if location is None: return new_status if self._comparison_operator(calculate_distance( location, self._target_location), self._distance): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTriggerDistanceToNextIntersection(AtomicCondition): """ This class contains the trigger (condition) for a distance to the next intersection of a scenario Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - distance: Trigger distance between the actor and the next intersection in meters The condition terminates with SUCCESS, when the actor reached the target distance to the next intersection """ def __init__(self, actor, distance, name="InTriggerDistanceToNextIntersection"): """ Setup trigger distance """ super(InTriggerDistanceToNextIntersection, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._distance = distance self._map = CarlaDataProvider.get_map() waypoint = self._map.get_waypoint(self._actor.get_location()) while waypoint and not waypoint.is_intersection: waypoint = waypoint.next(1)[-1] self._final_location = waypoint.transform.location def update(self): """ Check if the actor is within trigger distance to the intersection """ new_status = py_trees.common.Status.RUNNING current_waypoint = self._map.get_waypoint(CarlaDataProvider.get_location(self._actor)) distance = calculate_distance(current_waypoint.transform.location, self._final_location) if distance < self._distance: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTriggerDistanceToLocationAlongRoute(AtomicCondition): """ Implementation for a behavior that will check if a given actor is within a given distance to a given location considering a given route Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - distance: Trigger distance between the actor and the next intersection in meters - route: Route to be checked - location: Location on the route to be checked The condition terminates with SUCCESS, when the actor reached the target distance along its route to the given location """ def __init__(self, actor, route, location, distance, name="InTriggerDistanceToLocationAlongRoute"): """ Setup class members """ super(InTriggerDistanceToLocationAlongRoute, self).__init__(name) self._map = CarlaDataProvider.get_map() self._actor = actor self._location = location self._route = route self._distance = distance self._location_distance, _ = get_distance_along_route(self._route, self._location) def update(self): new_status = py_trees.common.Status.RUNNING current_location = CarlaDataProvider.get_location(self._actor) if current_location is None: return new_status if current_location.distance(self._location) < self._distance + 20: actor_distance, _ = get_distance_along_route(self._route, current_location) # If closer than self._distance and hasn't passed the trigger point if (self._location_distance < actor_distance + self._distance and actor_distance < self._location_distance) or \ self._location_distance < 1.0: new_status = py_trees.common.Status.SUCCESS return new_status class InTimeToArrivalToLocation(AtomicCondition): """ This class contains a check if a actor arrives within a given time at a given location. Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - time: The behavior is successful, if TTA is less than _time_ in seconds - location: Location to be checked in this behavior The condition terminates with SUCCESS, when the actor can reach the target location within the given time """ _max_time_to_arrival = float('inf') # time to arrival in seconds def __init__(self, actor, time, location, comparison_operator=operator.lt, name="TimeToArrival"): """ Setup parameters """ super(InTimeToArrivalToLocation, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._time = time self._target_location = location self._comparison_operator = comparison_operator def update(self): """ Check if the actor can arrive at target_location within time """ new_status = py_trees.common.Status.RUNNING current_location = CarlaDataProvider.get_location(self._actor) if current_location is None: return new_status distance = calculate_distance(current_location, self._target_location) velocity = CarlaDataProvider.get_velocity(self._actor) # if velocity is too small, simply use a large time to arrival time_to_arrival = self._max_time_to_arrival if velocity > EPSILON: time_to_arrival = distance / velocity if self._comparison_operator(time_to_arrival, self._time): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTimeToArrivalToVehicle(AtomicCondition): """ This class contains a check if a actor arrives within a given time at another actor. Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - time: The behavior is successful, if TTA is less than _time_ in seconds - other_actor: Reference actor used in this behavior The condition terminates with SUCCESS, when the actor can reach the other vehicle within the given time """ _max_time_to_arrival = float('inf') # time to arrival in seconds def __init__(self, actor, other_actor, time, along_route=False, comparison_operator=operator.lt, name="TimeToArrival"): """ Setup parameters """ super(InTimeToArrivalToVehicle, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._map = CarlaDataProvider.get_map() self._actor = actor self._other_actor = other_actor self._time = time self._along_route = along_route self._comparison_operator = comparison_operator if self._along_route: # Get the global route planner, used to calculate the route dao = GlobalRoutePlannerDAO(self._map, 0.5) grp = GlobalRoutePlanner(dao) grp.setup() self._grp = grp else: self._grp = None def update(self): """ Check if the ego vehicle can arrive at other actor within time """ new_status = py_trees.common.Status.RUNNING current_location = CarlaDataProvider.get_location(self._actor) other_location = CarlaDataProvider.get_location(self._other_actor) if current_location is None or other_location is None: return new_status current_velocity = CarlaDataProvider.get_velocity(self._actor) other_velocity = CarlaDataProvider.get_velocity(self._other_actor) if self._along_route: # Global planner needs a location at a driving lane current_location = self._map.get_waypoint(current_location).transform.location other_location = self._map.get_waypoint(other_location).transform.location distance = calculate_distance(current_location, other_location, self._grp) # if velocity is too small, simply use a large time to arrival time_to_arrival = self._max_time_to_arrival if current_velocity > other_velocity: time_to_arrival = 2 * distance / (current_velocity - other_velocity) if self._comparison_operator(time_to_arrival, self._time): new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class InTimeToArrivalToVehicleSideLane(InTimeToArrivalToLocation): """ This class contains a check if a actor arrives within a given time at another actor's side lane. Inherits from InTimeToArrivalToLocation Important parameters: - actor: CARLA actor to execute the behavior - name: Name of the condition - time: The behavior is successful, if TTA is less than _time_ in seconds - cut_in_lane: the lane from where the other_actor will do the cut in - other_actor: Reference actor used in this behavior The condition terminates with SUCCESS, when the actor can reach the other vehicle within the given time """ _max_time_to_arrival = float('inf') # time to arrival in seconds def __init__(self, actor, other_actor, time, side_lane, comparison_operator=operator.lt, name="InTimeToArrivalToVehicleSideLane"): """ Setup parameters """ self._other_actor = other_actor self._side_lane = side_lane self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map(self._world) other_location = other_actor.get_transform().location other_waypoint = self._map.get_waypoint(other_location) if self._side_lane == 'right': other_side_waypoint = other_waypoint.get_left_lane() elif self._side_lane == 'left': other_side_waypoint = other_waypoint.get_right_lane() else: raise Exception("cut_in_lane must be either 'left' or 'right'") other_side_location = other_side_waypoint.transform.location super(InTimeToArrivalToVehicleSideLane, self).__init__( actor, time, other_side_location, comparison_operator, name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): """ Check if the ego vehicle can arrive at other actor within time """ new_status = py_trees.common.Status.RUNNING other_location = CarlaDataProvider.get_location(self._other_actor) other_waypoint = self._map.get_waypoint(other_location) if self._side_lane == 'right': other_side_waypoint = other_waypoint.get_left_lane() elif self._side_lane == 'left': other_side_waypoint = other_waypoint.get_right_lane() else: raise Exception("cut_in_lane must be either 'left' or 'right'") if other_side_waypoint is None: return new_status self._target_location = other_side_waypoint.transform.location if self._target_location is None: return new_status new_status = super(InTimeToArrivalToVehicleSideLane, self).update() return new_status class WaitUntilInFront(AtomicCondition): """ Behavior that support the creation of cut ins. It waits until the actor has passed another actor Parameters: - actor: the one getting in front of the other actor - other_actor: the reference vehicle that the actor will have to get in front of - factor: How much in front the actor will have to get (from 0 to infinity): 0: They are right next to each other 1: The front of the other_actor and the back of the actor are right next to each other """ def __init__(self, actor, other_actor, factor=1, check_distance=True, name="WaitUntilInFront"): """ Init """ super(WaitUntilInFront, self).__init__(name) self._actor = actor self._other_actor = other_actor self._distance = 10 self._factor = max(EPSILON, factor) # Must be > 0 self._check_distance = check_distance self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map(self._world) actor_extent = self._actor.bounding_box.extent.x other_extent = self._other_actor.bounding_box.extent.x self._length = self._factor * (actor_extent + other_extent) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): """ Checks if the two actors meet the requirements """ new_status = py_trees.common.Status.RUNNING in_front = False close_by = False # Location of our actor actor_location = CarlaDataProvider.get_location(self._actor) if actor_location is None: return new_status # Waypoint in front of the other actor other_location = CarlaDataProvider.get_location(self._other_actor) other_waypoint = self._map.get_waypoint(other_location) if other_waypoint is None: return new_status other_next_waypoints = other_waypoint.next(self._length) if other_next_waypoints is None: return new_status other_next_waypoint = other_next_waypoints[0] # Wait for the vehicle to be in front other_dir = other_next_waypoint.transform.get_forward_vector() act_other_dir = actor_location - other_next_waypoint.transform.location dot_ve_wp = other_dir.x * act_other_dir.x + other_dir.y * act_other_dir.y + other_dir.z * act_other_dir.z if dot_ve_wp > 0.0: in_front = True # Wait for it to be close-by if not self._check_distance: close_by = True elif actor_location.distance(other_next_waypoint.transform.location) < self._distance: close_by = True if in_front and close_by: new_status = py_trees.common.Status.SUCCESS return new_status class DriveDistance(AtomicCondition): """ This class contains an atomic behavior to drive a certain distance. Important parameters: - actor: CARLA actor to execute the condition - distance: Distance for this condition in meters The condition terminates with SUCCESS, when the actor drove at least the given distance """ def __init__(self, actor, distance, name="DriveDistance"): """ Setup parameters """ super(DriveDistance, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._target_distance = distance self._distance = 0 self._location = None self._actor = actor def initialise(self): self._location = CarlaDataProvider.get_location(self._actor) super(DriveDistance, self).initialise() def update(self): """ Check driven distance """ new_status = py_trees.common.Status.RUNNING new_location = CarlaDataProvider.get_location(self._actor) self._distance += calculate_distance(self._location, new_location) self._location = new_location if self._distance > self._target_distance: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class AtRightmostLane(AtomicCondition): """ This class contains an atomic behavior to check if the actor is at the rightest driving lane. Important parameters: - actor: CARLA actor to execute the condition The condition terminates with SUCCESS, when the actor enters the rightest lane """ def __init__(self, actor, name="AtRightmostLane"): """ Setup parameters """ super(AtRightmostLane, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._map = CarlaDataProvider.get_map() def update(self): """ Check actor waypoints """ new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self._actor) waypoint = self._map.get_waypoint(location) if waypoint is None: return new_status right_waypoint = waypoint.get_right_lane() if right_waypoint is None: return new_status lane_type = right_waypoint.lane_type if lane_type != carla.LaneType.Driving: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class WaitForTrafficLightState(AtomicCondition): """ This class contains an atomic behavior to wait for a given traffic light to have the desired state. Args: actor (carla.TrafficLight): CARLA traffic light to execute the condition state (carla.TrafficLightState): State to be checked in this condition The condition terminates with SUCCESS, when the traffic light switches to the desired state """ def __init__(self, actor, state, name="WaitForTrafficLightState"): """ Setup traffic_light """ super(WaitForTrafficLightState, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor if "traffic_light" in actor.type_id else None self._state = state def update(self): """ Set status to SUCCESS, when traffic light state matches the expected one """ if self._actor is None: return py_trees.common.Status.FAILURE new_status = py_trees.common.Status.RUNNING if self._actor.state == self._state: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class WaitEndIntersection(AtomicCondition): """ Atomic behavior that waits until the vehicles has gone outside the junction. If currently inside no intersection, it will wait until one is found """ def __init__(self, actor, debug=False, name="WaitEndIntersection"): super(WaitEndIntersection, self).__init__(name) self.actor = actor self.debug = debug self.inside_junction = False self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): new_status = py_trees.common.Status.RUNNING location = CarlaDataProvider.get_location(self.actor) waypoint = CarlaDataProvider.get_map().get_waypoint(location) # Wait for the actor to enter a junction if not self.inside_junction and waypoint.is_junction: self.inside_junction = True # And to leave it if self.inside_junction and not waypoint.is_junction: if self.debug: print("--- Leaving the junction") new_status = py_trees.common.Status.SUCCESS return new_status class WaitForBlackboardVariable(AtomicCondition): """ Atomic behavior that keeps running until the blackboard variable is set to the corresponding value. Used to avoid returning FAILURE if the blackboard comparison fails. It also initially sets the variable to a given value, if given """ def __init__(self, variable_name, variable_value, var_init_value=None, debug=False, name="WaitForBlackboardVariable"): super(WaitForBlackboardVariable, self).__init__(name) self._debug = debug self._variable_name = variable_name self._variable_value = variable_value self.logger.debug("%s.__init__()" % (self.__class__.__name__)) if var_init_value is not None: blackboard = py_trees.blackboard.Blackboard() _ = blackboard.set(variable_name, var_init_value) def update(self): new_status = py_trees.common.Status.RUNNING blackv = py_trees.blackboard.Blackboard() value = blackv.get(self._variable_name) if value == self._variable_value: if self._debug: print("Blackboard variable {} set to True".format(self._variable_name)) new_status = py_trees.common.Status.SUCCESS return new_status ================================================ FILE: scenario_runner/srunner/scenariomanager/timer.py ================================================ #!/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 access to the CARLA game time and contains a py_trees timeout behavior using the CARLA game time """ import datetime import py_trees class GameTime(object): """ This (static) class provides access to the CARLA game time. The elapsed game time can be simply retrieved by calling: GameTime.get_time() """ _current_game_time = 0.0 # Elapsed game time after starting this Timer _carla_time = 0.0 _last_frame = 0 _platform_timestamp = 0 _init = False @staticmethod def on_carla_tick(timestamp): """ Callback receiving the CARLA time Update time only when frame is more recent that last frame """ if GameTime._last_frame < timestamp.frame: frames = timestamp.frame - GameTime._last_frame if GameTime._init else 1 GameTime._current_game_time += timestamp.delta_seconds * frames GameTime._last_frame = timestamp.frame GameTime._platform_timestamp = datetime.datetime.now() GameTime._init = True GameTime._carla_time = timestamp.elapsed_seconds @staticmethod def restart(): """ Reset game timer to 0 """ GameTime._current_game_time = 0.0 GameTime._init = False @staticmethod def get_time(): """ Returns elapsed game time """ return GameTime._current_game_time @staticmethod def get_carla_time(): """ Returns elapsed game time """ return GameTime._carla_time @staticmethod def get_wallclocktime(): """ Returns elapsed game time """ return GameTime._platform_timestamp @staticmethod def get_frame(): """ Returns elapsed game time """ return GameTime._last_frame class SimulationTimeCondition(py_trees.behaviour.Behaviour): """ This class contains an atomic simulation time condition behavior. It uses the CARLA game time, not the system time which is used by the py_trees timer. Returns, if the provided success_rule (greaterThan, lessThan, equalTo) was successfully evaluated """ def __init__(self, timeout, success_rule="greaterThan", name="SimulationTimeCondition"): """ Setup timeout """ super(SimulationTimeCondition, self).__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._timeout_value = timeout self._start_time = 0.0 self._success_rule = success_rule self._ops = {"greaterThan": (lambda x, y: x > y), "equalTo": (lambda x, y: x == y), "lessThan": (lambda x, y: x < y)} def initialise(self): """ Set start_time to current GameTime """ self._start_time = GameTime.get_time() self.logger.debug("%s.initialise()" % (self.__class__.__name__)) def update(self): """ Get current game time, and compare it to the timeout value Upon successfully comparison using the provided success_rule operator, the status changes to SUCCESS """ elapsed_time = GameTime.get_time() - self._start_time if not self._ops[self._success_rule](elapsed_time, self._timeout_value): new_status = py_trees.common.Status.RUNNING else: new_status = py_trees.common.Status.SUCCESS self.logger.debug("%s.update()[%s->%s]" % (self.__class__.__name__, self.status, new_status)) return new_status class TimeOut(SimulationTimeCondition): """ This class contains an atomic timeout behavior. It uses the CARLA game time, not the system time which is used by the py_trees timer. """ def __init__(self, timeout, name="TimeOut"): """ Setup timeout """ super(TimeOut, self).__init__(timeout, name=name) self.timeout = False def update(self): """ Upon reaching the timeout value the status changes to SUCCESS """ new_status = super(TimeOut, self).update() if new_status == py_trees.common.Status.SUCCESS: self.timeout = True return new_status ================================================ FILE: scenario_runner/srunner/scenariomanager/traffic_events.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ Collection of TrafficEvents """ from enum import Enum class TrafficEventType(Enum): """ This enum represents different traffic events that occur during driving. """ NORMAL_DRIVING = 0 COLLISION_STATIC = 1 COLLISION_VEHICLE = 2 COLLISION_PEDESTRIAN = 3 ROUTE_DEVIATION = 4 ROUTE_COMPLETION = 5 ROUTE_COMPLETED = 6 TRAFFIC_LIGHT_INFRACTION = 7 WRONG_WAY_INFRACTION = 8 ON_SIDEWALK_INFRACTION = 9 STOP_INFRACTION = 10 OUTSIDE_LANE_INFRACTION = 11 OUTSIDE_ROUTE_LANES_INFRACTION = 12 VEHICLE_BLOCKED = 13 class TrafficEvent(object): """ TrafficEvent definition """ def __init__(self, event_type, message=None, dictionary=None): """ Initialize object :param event_type: TrafficEventType defining the type of traffic event :param message: optional message to inform users of the event :param dictionary: optional dictionary with arbitrary keys and values """ self._type = event_type self._message = message self._dict = dictionary def get_type(self): """ @return type """ return self._type def get_message(self): """ @return message """ if self._message: return self._message return "" def set_message(self, message): """ Set message """ self._message = message def get_dict(self): """ @return dictionary """ return self._dict def set_dict(self, dictionary): """ Set dictionary """ self._dict = dictionary ================================================ FILE: scenario_runner/srunner/scenariomanager/watchdog.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a simple watchdog timer to detect timeouts It is for example used in the ScenarioManager """ from __future__ import print_function from threading import Timer try: import thread except ImportError: import _thread as thread class Watchdog(object): """ Simple watchdog timer to detect timeouts Args: timeout (float): Timeout value of the watchdog [seconds]. If it is not reset before exceeding this value, a KayboardInterrupt is raised. Attributes: _timeout (float): Timeout value of the watchdog [seconds]. _failed (bool): True if watchdog exception occured, false otherwise """ def __init__(self, timeout=1.0): """ Class constructor """ self._timeout = timeout + 1.0 # Let's add one second here to avoid overlap with other CARLA timeouts self._failed = False self._timer = None def start(self): """ Start the watchdog """ self._timer = Timer(self._timeout, self._event) self._timer.daemon = True self._timer.start() def update(self): """ Reset watchdog. """ self.stop() self.start() def _event(self): """ This method is called when the timer triggers. A KayboardInterrupt is generated on the main thread and the watchdog is stopped. """ print('Watchdog exception - Timeout of {} seconds occured'.format(self._timeout)) self._failed = True self.stop() thread.interrupt_main() def stop(self): """ Stops the watchdog. """ self._timer.cancel() def get_status(self): """ returns: bool: False if watchdog exception occured, True otherwise """ return not self._failed ================================================ FILE: scenario_runner/srunner/scenariomanager/weather_sim.py ================================================ #!/usr/bin/env python # Copyright (c) 2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides a weather class and py_trees behavior to simulate weather in CARLA according to the astronomic behavior of the sun. """ import datetime import math import operator import ephem import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import GameTime class Weather(object): """ Class to simulate weather in CARLA according to the astronomic behavior of the sun The sun position (azimuth and altitude angles) is obtained by calculating its astronomic position for the CARLA reference position (x=0, y=0, z=0) using the ephem library. Args: carla_weather (carla.WeatherParameters): Initial weather settings. dtime (datetime): Initial date and time in UTC (required for animation only). Defaults to None. animation (bool): Flag to allow animating the sun position over time. Defaults to False. Attributes: carla_weather (carla.WeatherParameters): Weather parameters for CARLA. animation (bool): Flag to allow animating the sun position over time. _sun (ephem.Sun): The sun as astronomic entity. _observer_location (ephem.Observer): Holds the geographical position (lat/lon/altitude) for which the sun position is obtained. datetime (datetime): Date and time in UTC (required for animation only). """ def __init__(self, carla_weather, dtime=None, animation=False): """ Class constructor """ self.carla_weather = carla_weather self.animation = animation self._sun = ephem.Sun() # pylint: disable=no-member self._observer_location = ephem.Observer() geo_location = CarlaDataProvider.get_map().transform_to_geolocation(carla.Location(0, 0, 0)) self._observer_location.lon = str(geo_location.longitude) self._observer_location.lat = str(geo_location.latitude) self.datetime = dtime if self.datetime: self._observer_location.date = self.datetime self.update() def update(self, delta_time=0): """ If the weather animation is true, the new sun position is calculated w.r.t delta_time Nothing happens if animation or datetime are None. Args: delta_time (float): Time passed since self.datetime [seconds]. """ if not self.animation or not self.datetime: return self.datetime = self.datetime + datetime.timedelta(seconds=delta_time) self._observer_location.date = self.datetime self._sun.compute(self._observer_location) self.carla_weather.sun_altitude_angle = math.degrees(self._sun.alt) self.carla_weather.sun_azimuth_angle = math.degrees(self._sun.az) class WeatherBehavior(py_trees.behaviour.Behaviour): """ Atomic to read weather settings from the blackboard and apply these in CARLA. Used in combination with UpdateWeather() to have a continuous weather simulation. This behavior is always in a running state and must never terminate. The user must not add this behavior. It is automatically added by the ScenarioManager. This atomic also sets the datetime to blackboard variable, used by TimeOfDayComparison atomic Args: name (string): Name of the behavior. Defaults to 'WeatherBehavior'. Attributes: _weather (srunner.scenariomanager.weather_sim.Weather): Weather settings. _current_time (float): Current CARLA time [seconds]. """ def __init__(self, name="WeatherBehavior"): """ Setup parameters """ super(WeatherBehavior, self).__init__(name) self._weather = None self._current_time = None def initialise(self): """ Set current time to current CARLA time """ self._current_time = GameTime.get_time() def update(self): """ Check if new weather settings are available on the blackboard, and if yes fetch these into the _weather attribute. Apply the weather settings from _weather to CARLA. Note: To minimize CARLA server interactions, the weather is only updated, when the blackboard is updated, or if the weather animation flag is true. In the latter case, the update frequency is 1 Hz. returns: py_trees.common.Status.RUNNING """ weather = None try: check_weather = operator.attrgetter("CarlaWeather") weather = check_weather(py_trees.blackboard.Blackboard()) except AttributeError: pass if weather: self._weather = weather delattr(py_trees.blackboard.Blackboard(), "CarlaWeather") CarlaDataProvider.get_world().set_weather(self._weather.carla_weather) py_trees.blackboard.Blackboard().set("Datetime", self._weather.datetime, overwrite=True) if self._weather and self._weather.animation: new_time = GameTime.get_time() delta_time = new_time - self._current_time if delta_time > 1: self._weather.update(delta_time) self._current_time = new_time CarlaDataProvider.get_world().set_weather(self._weather.carla_weather) py_trees.blackboard.Blackboard().set("Datetime", self._weather.datetime, overwrite=True) return py_trees.common.Status.RUNNING ================================================ FILE: scenario_runner/srunner/scenarios/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/scenarios/background_activity.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Scenario spawning elements to make the town dynamic and interesting """ import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenarios.basic_scenario import BasicScenario import os class BackgroundActivity(BasicScenario): """ Implementation of a scenario to spawn a set of background actors, and to remove traffic jams in background traffic This is a single ego vehicle scenario """ town_amount = { 'Town01': 120, 'Town02': 100, 'Town03': 120, 'Town04': 200, 'Town05': 120, 'Town06': 150, 'Town07': 110, 'Town08': 180, 'Town09': 300, 'Town10': 120, } def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, timeout=35 * 60): """ Setup all relevant parameters and create scenario """ self.config = config self.debug = debug_mode self.timeout = timeout # Timeout of scenario in seconds super(BackgroundActivity, self).__init__("BackgroundActivity", ego_vehicles, config, world, debug_mode, terminate_on_failure=True, criteria_enable=True) def _initialize_actors(self, config): town_name = config.town if town_name in self.town_amount: amount = self.town_amount[town_name] else: amount = 0 if os.environ["BENCHMARK"] == "town05long": amount = 120 print("----------------Eval with Town05 Long, amount=120", flush=True) if os.environ["BENCHMARK"] == "longest6": amount = 500 print("----------------Eval with Longest6, amount=500", flush=True) new_actors = CarlaDataProvider.request_new_batch_actors('vehicle.*', amount, carla.Transform(), autopilot=True, random_location=True, rolename='background') if new_actors is None: raise Exception("Error: Unable to add the background activity, all spawn points were occupied") for _actor in new_actors: self.other_actors.append(_actor) def _create_behavior(self): """ Basic behavior do nothing, i.e. Idle """ pass def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ pass def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/basic_scenario.py ================================================ #!/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 provide BasicScenario, the basic class of all the scenarios. """ from __future__ import print_function import operator import py_trees import carla import srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions as conditions from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.timer import TimeOut from srunner.scenariomanager.weather_sim import WeatherBehavior from srunner.scenariomanager.scenarioatomics.atomic_behaviors import UpdateAllActorControls class BasicScenario(object): """ Base class for user-defined scenario """ def __init__(self, name, ego_vehicles, config, world, debug_mode=False, terminate_on_failure=False, criteria_enable=False): """ Setup all relevant parameters and create scenario and instantiate scenario manager """ self.other_actors = [] if not self.timeout: # pylint: disable=access-member-before-definition self.timeout = 60 # If no timeout was provided, set it to 60 seconds self.criteria_list = [] # List of evaluation criteria self.scenario = None self.ego_vehicles = ego_vehicles self.name = name self.config = config self.terminate_on_failure = terminate_on_failure self._initialize_environment(world) # Initializing adversarial actors self._initialize_actors(config) if CarlaDataProvider.is_sync_mode(): world.tick() else: world.wait_for_tick() # Setup scenario if debug_mode: py_trees.logging.level = py_trees.logging.Level.DEBUG behavior = self._create_behavior() criteria = None if criteria_enable: criteria = self._create_test_criteria() # Add a trigger condition for the behavior to ensure the behavior is only activated, when it is relevant behavior_seq = py_trees.composites.Sequence() trigger_behavior = self._setup_scenario_trigger(config) if trigger_behavior: behavior_seq.add_child(trigger_behavior) if behavior is not None: behavior_seq.add_child(behavior) behavior_seq.name = behavior.name end_behavior = self._setup_scenario_end(config) if end_behavior: behavior_seq.add_child(end_behavior) self.scenario = Scenario(behavior_seq, criteria, self.name, self.timeout, self.terminate_on_failure) def _initialize_environment(self, world): """ Default initialization of weather and road friction. Override this method in child class to provide custom initialization. """ # Set the appropriate weather conditions world.set_weather(self.config.weather) # Set the appropriate road friction if self.config.friction is not None: friction_bp = world.get_blueprint_library().find('static.trigger.friction') extent = carla.Location(1000000.0, 1000000.0, 1000000.0) friction_bp.set_attribute('friction', str(self.config.friction)) friction_bp.set_attribute('extent_x', str(extent.x)) friction_bp.set_attribute('extent_y', str(extent.y)) friction_bp.set_attribute('extent_z', str(extent.z)) # Spawn Trigger Friction transform = carla.Transform() transform.location = carla.Location(-10000.0, -10000.0, 0.0) world.spawn_actor(friction_bp, transform) def _initialize_actors(self, config): """ Default initialization of other actors. Override this method in child class to provide custom initialization. """ if config.other_actors: new_actors = CarlaDataProvider.request_new_actors(config.other_actors) if not new_actors: raise Exception("Error: Unable to add actors") for new_actor in new_actors: self.other_actors.append(new_actor) def _setup_scenario_trigger(self, config): """ This function creates a trigger maneuver, that has to be finished before the real scenario starts. This implementation focuses on the first available ego vehicle. The function can be overloaded by a user implementation inside the user-defined scenario class. """ start_location = None if config.trigger_points and config.trigger_points[0]: start_location = config.trigger_points[0].location # start location of the scenario ego_vehicle_route = CarlaDataProvider.get_ego_vehicle_route() if start_location: if ego_vehicle_route: if config.route_var_name is None: # pylint: disable=no-else-return return conditions.InTriggerDistanceToLocationAlongRoute(self.ego_vehicles[0], ego_vehicle_route, start_location, 5) else: check_name = "WaitForBlackboardVariable: {}".format(config.route_var_name) return conditions.WaitForBlackboardVariable(name=check_name, variable_name=config.route_var_name, variable_value=True, var_init_value=False) return conditions.InTimeToArrivalToLocation(self.ego_vehicles[0], 2.0, start_location) return None def _setup_scenario_end(self, config): """ This function adds and additional behavior to the scenario, which is triggered after it has ended. The function can be overloaded by a user implementation inside the user-defined scenario class. """ ego_vehicle_route = CarlaDataProvider.get_ego_vehicle_route() if ego_vehicle_route: if config.route_var_name is not None: set_name = "Reset Blackboard Variable: {} ".format(config.route_var_name) return py_trees.blackboard.SetBlackboardVariable(name=set_name, variable_name=config.route_var_name, variable_value=False) return None def _create_behavior(self): """ Pure virtual function to setup user-defined scenario behavior """ raise NotImplementedError( "This function is re-implemented by all scenarios" "If this error becomes visible the class hierarchy is somehow broken") def _create_test_criteria(self): """ Pure virtual function to setup user-defined evaluation criteria for the scenario """ raise NotImplementedError( "This function is re-implemented by all scenarios" "If this error becomes visible the class hierarchy is somehow broken") def change_control(self, control): # pylint: disable=no-self-use """ This is a function that changes the control based on the scenario determination :param control: a carla vehicle control :return: a control to be changed by the scenario. Note: This method should be overriden by the user-defined scenario behavior """ return control def remove_all_actors(self): """ Remove all actors """ for i, _ in enumerate(self.other_actors): if self.other_actors[i] is not None: if CarlaDataProvider.actor_id_exists(self.other_actors[i].id): CarlaDataProvider.remove_actor_by_id(self.other_actors[i].id) self.other_actors[i] = None self.other_actors = [] class Scenario(object): """ Basic scenario class. This class holds the behavior_tree describing the scenario and the test criteria. The user must not modify this class. Important parameters: - behavior: User defined scenario with py_tree - criteria_list: List of user defined test criteria with py_tree - timeout (default = 60s): Timeout of the scenario in seconds - terminate_on_failure: Terminate scenario on first failure """ def __init__(self, behavior, criteria, name, timeout=60, terminate_on_failure=False): self.behavior = behavior self.test_criteria = criteria self.timeout = timeout self.name = name if self.test_criteria is not None and not isinstance(self.test_criteria, py_trees.composites.Parallel): # list of nodes for criterion in self.test_criteria: criterion.terminate_on_failure = terminate_on_failure # Create py_tree for test criteria self.criteria_tree = py_trees.composites.Parallel( name="Test Criteria", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE ) self.criteria_tree.add_children(self.test_criteria) self.criteria_tree.setup(timeout=1) else: self.criteria_tree = criteria # Create node for timeout self.timeout_node = TimeOut(self.timeout, name="TimeOut") # Create overall py_tree self.scenario_tree = py_trees.composites.Parallel(name, policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) if behavior is not None: self.scenario_tree.add_child(self.behavior) self.scenario_tree.add_child(self.timeout_node) self.scenario_tree.add_child(WeatherBehavior()) self.scenario_tree.add_child(UpdateAllActorControls()) if criteria is not None: self.scenario_tree.add_child(self.criteria_tree) self.scenario_tree.setup(timeout=1) def _extract_nodes_from_tree(self, tree): # pylint: disable=no-self-use """ Returns the list of all nodes from the given tree """ node_list = [tree] more_nodes_exist = True while more_nodes_exist: more_nodes_exist = False for node in node_list: if node.children: node_list.remove(node) more_nodes_exist = True for child in node.children: node_list.append(child) if len(node_list) == 1 and isinstance(node_list[0], py_trees.composites.Parallel): return [] return node_list def get_criteria(self): """ Return the list of test criteria (all leave nodes) """ criteria_list = self._extract_nodes_from_tree(self.criteria_tree) return criteria_list def terminate(self): """ This function sets the status of all leaves in the scenario tree to INVALID """ # Get list of all nodes in the tree node_list = self._extract_nodes_from_tree(self.scenario_tree) # Set status to INVALID for node in node_list: node.terminate(py_trees.common.Status.INVALID) # Cleanup all instantiated controllers actor_dict = {} try: check_actors = operator.attrgetter("ActorsWithController") actor_dict = check_actors(py_trees.blackboard.Blackboard()) except AttributeError: pass for actor_id in actor_dict: actor_dict[actor_id].reset() py_trees.blackboard.Blackboard().set("ActorsWithController", {}, overwrite=True) ================================================ FILE: scenario_runner/srunner/scenarios/change_lane.py ================================================ #!/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 . """ Change lane scenario: The scenario realizes a driving behavior, in which the user-controlled ego vehicle follows a fast driving car on the highway. There's a slow car driving in great distance to the fast vehicle. At one point the fast vehicle is changing the lane to overtake a slow car, which is driving on the same lane. The ego vehicle doesn't "see" the slow car before the lane change of the fast car, therefore it hast to react fast to avoid an collision. There are two options to avoid an accident: The ego vehicle adjusts its velocity or changes the lane as well. """ import random import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, StopVehicle, LaneChange, WaypointFollower, Idle) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle, StandStill from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import get_waypoint_in_distance class ChangeLane(BasicScenario): """ This class holds everything required for a "change lane" scenario involving three vehicles. There are two vehicles driving in the same direction on the highway: A fast car and a slow car in front. The fast car will change the lane, when it is close to the slow car. The ego vehicle is driving right behind the fast car. This is a single ego vehicle scenario """ timeout = 1200 def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=600): """ Setup all relevant parameters and create scenario If randomize is True, the scenario parameters are randomized """ self.timeout = timeout self._map = CarlaDataProvider.get_map() self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self._fast_vehicle_velocity = 70 self._slow_vehicle_velocity = 0 self._change_lane_velocity = 15 self._slow_vehicle_distance = 100 self._fast_vehicle_distance = 20 self._trigger_distance = 30 self._max_brake = 1 self.direction = 'left' # direction of lane change self.lane_check = 'true' # check whether a lane change is possible super(ChangeLane, self).__init__("ChangeLane", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) if randomize: self._fast_vehicle_distance = random.randint(10, 51) self._fast_vehicle_velocity = random.randint(100, 201) self._slow_vehicle_velocity = random.randint(1, 6) def _initialize_actors(self, config): # add actors from xml file for actor in config.other_actors: vehicle = CarlaDataProvider.request_new_actor(actor.model, actor.transform) self.other_actors.append(vehicle) vehicle.set_simulate_physics(enabled=False) # fast vehicle, tesla # transform visible fast_car_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._fast_vehicle_distance) self.fast_car_visible = carla.Transform( carla.Location(fast_car_waypoint.transform.location.x, fast_car_waypoint.transform.location.y, fast_car_waypoint.transform.location.z + 1), fast_car_waypoint.transform.rotation) # slow vehicle, vw # transform visible slow_car_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._slow_vehicle_distance) self.slow_car_visible = carla.Transform( carla.Location(slow_car_waypoint.transform.location.x, slow_car_waypoint.transform.location.y, slow_car_waypoint.transform.location.z), slow_car_waypoint.transform.rotation) def _create_behavior(self): # sequence vw # make visible sequence_vw = py_trees.composites.Sequence("VW T2") vw_visible = ActorTransformSetter(self.other_actors[1], self.slow_car_visible) sequence_vw.add_child(vw_visible) # brake, avoid rolling backwarts brake = StopVehicle(self.other_actors[1], self._max_brake) sequence_vw.add_child(brake) sequence_vw.add_child(Idle()) # sequence tesla # make visible sequence_tesla = py_trees.composites.Sequence("Tesla") tesla_visible = ActorTransformSetter(self.other_actors[0], self.fast_car_visible) sequence_tesla.add_child(tesla_visible) # drive fast towards slow vehicle just_drive = py_trees.composites.Parallel("DrivingTowardsSlowVehicle", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) tesla_driving_fast = WaypointFollower(self.other_actors[0], self._fast_vehicle_velocity) just_drive.add_child(tesla_driving_fast) distance_to_vehicle = InTriggerDistanceToVehicle( self.other_actors[1], self.other_actors[0], self._trigger_distance) just_drive.add_child(distance_to_vehicle) sequence_tesla.add_child(just_drive) # change lane lane_change_atomic = LaneChange(self.other_actors[0], distance_other_lane=200) sequence_tesla.add_child(lane_change_atomic) sequence_tesla.add_child(Idle()) # ego vehicle # end condition endcondition = py_trees.composites.Parallel("Waiting for end position of ego vehicle", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL) endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[1], self.ego_vehicles[0], distance=20, name="FinalDistance") endcondition_part2 = StandStill(self.ego_vehicles[0], name="FinalSpeed") endcondition.add_child(endcondition_part1) endcondition.add_child(endcondition_part2) # build tree root = py_trees.composites.Parallel("Parallel Behavior", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) root.add_child(sequence_vw) root.add_child(sequence_tesla) root.add_child(endcondition) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/control_loss.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Control Loss Vehicle scenario: The scenario realizes that the vehicle looses control due to bad road conditions, etc. and checks to see if the vehicle regains control and corrects it's course. """ import numpy.random as random import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeNoiseParameters, ActorTransformSetter from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation, InTriggerDistanceToNextIntersection, DriveDistance) from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import get_location_in_distance_from_wp class ControlLoss(BasicScenario): """ Implementation of "Control Loss Vehicle" (Traffic Scenario 01) This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario """ # ego vehicle parameters self._no_of_jitter = 10 self._noise_mean = 0 # Mean value of steering noise self._noise_std = 0.01 # Std. deviation of steering noise self._dynamic_mean_for_steer = 0.001 self._dynamic_mean_for_throttle = 0.045 self._abort_distance_to_intersection = 10 self._current_steer_noise = [0] # This is a list, since lists are mutable self._current_throttle_noise = [0] self._start_distance = 20 self._trigger_dist = 2 self._end_distance = 30 self._ego_vehicle_max_steer = 0.0 self._ego_vehicle_max_throttle = 1.0 self._ego_vehicle_target_velocity = 15 self._map = CarlaDataProvider.get_map() # Timeout of scenario in seconds self.timeout = timeout # The reference trigger for the control loss self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self.loc_list = [] self.obj = [] self._randomize = randomize super(ControlLoss, self).__init__("ControlLoss", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ if self._randomize: self._distance = random.randint(low=10, high=80, size=3) self._distance = sorted(self._distance) else: self._distance = [14, 48, 74] first_loc, _ = get_location_in_distance_from_wp(self._reference_waypoint, self._distance[0]) second_loc, _ = get_location_in_distance_from_wp(self._reference_waypoint, self._distance[1]) third_loc, _ = get_location_in_distance_from_wp(self._reference_waypoint, self._distance[2]) self.loc_list.extend([first_loc, second_loc, third_loc]) self._dist_prop = [x - 2 for x in self._distance] self.first_loc_prev, _ = get_location_in_distance_from_wp(self._reference_waypoint, self._dist_prop[0]) self.sec_loc_prev, _ = get_location_in_distance_from_wp(self._reference_waypoint, self._dist_prop[1]) self.third_loc_prev, _ = get_location_in_distance_from_wp(self._reference_waypoint, self._dist_prop[2]) self.first_transform = carla.Transform(self.first_loc_prev) self.sec_transform = carla.Transform(self.sec_loc_prev) self.third_transform = carla.Transform(self.third_loc_prev) self.first_transform = carla.Transform(carla.Location(self.first_loc_prev.x, self.first_loc_prev.y, self.first_loc_prev.z)) self.sec_transform = carla.Transform(carla.Location(self.sec_loc_prev.x, self.sec_loc_prev.y, self.sec_loc_prev.z)) self.third_transform = carla.Transform(carla.Location(self.third_loc_prev.x, self.third_loc_prev.y, self.third_loc_prev.z)) first_debris = CarlaDataProvider.request_new_actor('static.prop.dirtdebris01', self.first_transform, 'prop') second_debris = CarlaDataProvider.request_new_actor('static.prop.dirtdebris01', self.sec_transform, 'prop') third_debris = CarlaDataProvider.request_new_actor('static.prop.dirtdebris01', self.third_transform, 'prop') first_debris.set_transform(self.first_transform) second_debris.set_transform(self.sec_transform) third_debris.set_transform(self.third_transform) self.obj.extend([first_debris, second_debris, third_debris]) for debris in self.obj: debris.set_simulate_physics(False) self.other_actors.append(first_debris) self.other_actors.append(second_debris) self.other_actors.append(third_debris) def _create_behavior(self): """ The scenario defined after is a "control loss vehicle" scenario. After invoking this scenario, it will wait until the vehicle drove a few meters (_start_distance), and then perform a jitter action. Finally, the vehicle has to reach a target point (_end_distance). If this does not happen within 60 seconds, a timeout stops the scenario """ # start condition start_end_parallel = py_trees.composites.Parallel("Jitter", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) start_condition = InTriggerDistanceToLocation(self.ego_vehicles[0], self.first_loc_prev, self._trigger_dist) for _ in range(self._no_of_jitter): # change the current noise to be applied turn = ChangeNoiseParameters(self._current_steer_noise, self._current_throttle_noise, self._noise_mean, self._noise_std, self._dynamic_mean_for_steer, self._dynamic_mean_for_throttle) # Mean value of steering noise # Noise end! put again the added noise to zero. noise_end = ChangeNoiseParameters(self._current_steer_noise, self._current_throttle_noise, 0, 0, 0, 0) jitter_action = py_trees.composites.Parallel("Jitter", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) # Abort jitter_sequence, if the vehicle is approaching an intersection jitter_abort = InTriggerDistanceToNextIntersection(self.ego_vehicles[0], self._abort_distance_to_intersection) # endcondition: Check if vehicle reached waypoint _end_distance from here: end_condition = DriveDistance(self.ego_vehicles[0], self._end_distance) start_end_parallel.add_child(start_condition) start_end_parallel.add_child(end_condition) # Build behavior tree sequence = py_trees.composites.Sequence("ControlLoss") sequence.add_child(ActorTransformSetter(self.other_actors[0], self.first_transform, physics=False)) sequence.add_child(ActorTransformSetter(self.other_actors[1], self.sec_transform, physics=False)) sequence.add_child(ActorTransformSetter(self.other_actors[2], self.third_transform, physics=False)) jitter = py_trees.composites.Sequence("Jitter Behavior") jitter.add_child(turn) jitter.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], self.sec_loc_prev, self._trigger_dist)) jitter.add_child(turn) jitter.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], self.third_loc_prev, self._trigger_dist)) jitter.add_child(turn) jitter_action.add_child(jitter) jitter_action.add_child(jitter_abort) sequence.add_child(start_end_parallel) sequence.add_child(jitter_action) sequence.add_child(end_condition) sequence.add_child(noise_end) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def change_control(self, control): """ This is a function that changes the control based on the scenario determination :param control: a carla vehicle control :return: a control to be changed by the scenario. """ control.steer += self._current_steer_noise[0] control.throttle += self._current_throttle_noise[0] return control def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/cut_in.py ================================================ #!/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 . """ Cut in scenario: The scenario realizes a driving behavior on the highway. The user-controlled ego vehicle is driving straight and keeping its velocity at a constant level. Another car is cutting just in front, coming from left or right lane. The ego vehicle may need to brake to avoid a collision. """ import random import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, LaneChange, WaypointFollower, AccelerateToCatchUp) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerDistanceToVehicle, DriveDistance from srunner.scenarios.basic_scenario import BasicScenario class CutIn(BasicScenario): """ The ego vehicle is driving on a highway and another car is cutting in just in front. This is a single ego vehicle scenario """ timeout = 1200 def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=600): self.timeout = timeout self._map = CarlaDataProvider.get_map() self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self._velocity = 40 self._delta_velocity = 10 self._trigger_distance = 30 # get direction from config name self._config = config self._direction = None self._transform_visible = None super(CutIn, self).__init__("CutIn", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) if randomize: self._velocity = random.randint(20, 60) self._trigger_distance = random.randint(10, 40) def _initialize_actors(self, config): # direction of lane, on which other_actor is driving before lane change if 'LEFT' in self._config.name.upper(): self._direction = 'left' if 'RIGHT' in self._config.name.upper(): self._direction = 'right' # add actors from xml file for actor in config.other_actors: vehicle = CarlaDataProvider.request_new_actor(actor.model, actor.transform) self.other_actors.append(vehicle) vehicle.set_simulate_physics(enabled=False) # transform visible other_actor_transform = self.other_actors[0].get_transform() self._transform_visible = carla.Transform( carla.Location(other_actor_transform.location.x, other_actor_transform.location.y, other_actor_transform.location.z + 105), other_actor_transform.rotation) def _create_behavior(self): """ Order of sequence: - car_visible: spawn car at a visible transform - just_drive: drive until in trigger distance to ego_vehicle - accelerate: accelerate to catch up distance to ego_vehicle - lane_change: change the lane - endcondition: drive for a defined distance """ # car_visible behaviour = py_trees.composites.Sequence("CarOn_{}_Lane" .format(self._direction)) car_visible = ActorTransformSetter(self.other_actors[0], self._transform_visible) behaviour.add_child(car_visible) # just_drive just_drive = py_trees.composites.Parallel( "DrivingStraight", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) car_driving = WaypointFollower(self.other_actors[0], self._velocity) just_drive.add_child(car_driving) trigger_distance = InTriggerDistanceToVehicle( self.other_actors[0], self.ego_vehicles[0], self._trigger_distance) just_drive.add_child(trigger_distance) behaviour.add_child(just_drive) # accelerate accelerate = AccelerateToCatchUp(self.other_actors[0], self.ego_vehicles[0], throttle_value=1, delta_velocity=self._delta_velocity, trigger_distance=5, max_distance=500) behaviour.add_child(accelerate) # lane_change if self._direction == 'left': lane_change = LaneChange( self.other_actors[0], speed=None, direction='right', distance_same_lane=5, distance_other_lane=300) behaviour.add_child(lane_change) else: lane_change = LaneChange( self.other_actors[0], speed=None, direction='left', distance_same_lane=5, distance_other_lane=300) behaviour.add_child(lane_change) # endcondition endcondition = DriveDistance(self.other_actors[0], 200) # build tree root = py_trees.composites.Sequence("Behavior", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) root.add_child(behaviour) root.add_child(endcondition) return root def _create_test_criteria(self): """ A list of all test criteria is created, which is later used in the parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors after deletion. """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/follow_leading_vehicle.py ================================================ #!/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 . """ Follow leading vehicle scenario: The scenario realizes a common driving behavior, in which the user-controlled ego vehicle follows a leading car driving down a given road. At some point the leading car has to slow down and finally stop. The ego vehicle has to react accordingly to avoid a collision. The scenario ends either via a timeout, or if the ego vehicle stopped close enough to the leading vehicle """ import random import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, KeepVelocity, StopVehicle, WaypointFollower) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle, InTriggerDistanceToNextIntersection, DriveDistance, StandStill) from srunner.scenariomanager.timer import TimeOut from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import get_waypoint_in_distance class FollowLeadingVehicle(BasicScenario): """ This class holds everything required for a simple "Follow a leading vehicle" scenario involving two vehicles. (Traffic Scenario 2) This is a single ego vehicle scenario """ timeout = 120 # Timeout of scenario in seconds def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario If randomize is True, the scenario parameters are randomized """ self._map = CarlaDataProvider.get_map() self._first_vehicle_location = 25 self._first_vehicle_speed = 10 self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self._other_actor_max_brake = 1.0 self._other_actor_stop_in_front_intersection = 20 self._other_actor_transform = None # Timeout of scenario in seconds self.timeout = timeout super(FollowLeadingVehicle, self).__init__("FollowVehicle", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) if randomize: self._ego_other_distance_start = random.randint(4, 8) # Example code how to randomize start location # distance = random.randint(20, 80) # new_location, _ = get_location_in_distance(self.ego_vehicles[0], distance) # waypoint = CarlaDataProvider.get_map().get_waypoint(new_location) # waypoint.transform.location.z += 39 # self.other_actors[0].set_transform(waypoint.transform) def _initialize_actors(self, config): """ Custom initialization """ first_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location) self._other_actor_transform = carla.Transform( carla.Location(first_vehicle_waypoint.transform.location.x, first_vehicle_waypoint.transform.location.y, first_vehicle_waypoint.transform.location.z + 1), first_vehicle_waypoint.transform.rotation) first_vehicle_transform = carla.Transform( carla.Location(self._other_actor_transform.location.x, self._other_actor_transform.location.y, self._other_actor_transform.location.z - 500), self._other_actor_transform.rotation) first_vehicle = CarlaDataProvider.request_new_actor('vehicle.nissan.patrol', first_vehicle_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ The scenario defined after is a "follow leading vehicle" scenario. After invoking this scenario, it will wait for the user controlled vehicle to enter the start region, then make the other actor to drive until reaching the next intersection. Finally, the user-controlled vehicle has to be close enough to the other actor to end the scenario. If this does not happen within 60 seconds, a timeout stops the scenario """ # to avoid the other actor blocking traffic, it was spawed elsewhere # reset its pose to the required one start_transform = ActorTransformSetter(self.other_actors[0], self._other_actor_transform) # let the other actor drive until next intersection # We should add some feedback mechanism to respond to ego_vehicle behavior driving_to_next_intersection = py_trees.composites.Parallel( "DrivingTowardsIntersection", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) driving_to_next_intersection.add_child(WaypointFollower(self.other_actors[0], self._first_vehicle_speed)) driving_to_next_intersection.add_child(InTriggerDistanceToNextIntersection( self.other_actors[0], self._other_actor_stop_in_front_intersection)) # stop vehicle stop = StopVehicle(self.other_actors[0], self._other_actor_max_brake) # end condition endcondition = py_trees.composites.Parallel("Waiting for end position", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL) endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], distance=20, name="FinalDistance") endcondition_part2 = StandStill(self.ego_vehicles[0], name="StandStill", duration=1) endcondition.add_child(endcondition_part1) endcondition.add_child(endcondition_part2) # Build behavior tree sequence = py_trees.composites.Sequence("Sequence Behavior") sequence.add_child(start_transform) sequence.add_child(driving_to_next_intersection) sequence.add_child(stop) sequence.add_child(endcondition) sequence.add_child(ActorDestroy(self.other_actors[0])) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() class FollowLeadingVehicleWithObstacle(BasicScenario): """ This class holds a scenario similar to FollowLeadingVehicle but there is an obstacle in front of the leading vehicle This is a single ego vehicle scenario """ timeout = 120 # Timeout of scenario in seconds def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True): """ Setup all relevant parameters and create scenario """ self._map = CarlaDataProvider.get_map() self._first_actor_location = 25 self._second_actor_location = self._first_actor_location + 41 self._first_actor_speed = 10 self._second_actor_speed = 1.5 self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self._other_actor_max_brake = 1.0 self._first_actor_transform = None self._second_actor_transform = None super(FollowLeadingVehicleWithObstacle, self).__init__("FollowLeadingVehicleWithObstacle", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) if randomize: self._ego_other_distance_start = random.randint(4, 8) def _initialize_actors(self, config): """ Custom initialization """ first_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_actor_location) second_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_actor_location) first_actor_transform = carla.Transform( carla.Location(first_actor_waypoint.transform.location.x, first_actor_waypoint.transform.location.y, first_actor_waypoint.transform.location.z - 500), first_actor_waypoint.transform.rotation) self._first_actor_transform = carla.Transform( carla.Location(first_actor_waypoint.transform.location.x, first_actor_waypoint.transform.location.y, first_actor_waypoint.transform.location.z + 1), first_actor_waypoint.transform.rotation) yaw_1 = second_actor_waypoint.transform.rotation.yaw + 90 second_actor_transform = carla.Transform( carla.Location(second_actor_waypoint.transform.location.x, second_actor_waypoint.transform.location.y, second_actor_waypoint.transform.location.z - 500), carla.Rotation(second_actor_waypoint.transform.rotation.pitch, yaw_1, second_actor_waypoint.transform.rotation.roll)) self._second_actor_transform = carla.Transform( carla.Location(second_actor_waypoint.transform.location.x, second_actor_waypoint.transform.location.y, second_actor_waypoint.transform.location.z + 1), carla.Rotation(second_actor_waypoint.transform.rotation.pitch, yaw_1, second_actor_waypoint.transform.rotation.roll)) first_actor = CarlaDataProvider.request_new_actor( 'vehicle.nissan.patrol', first_actor_transform) second_actor = CarlaDataProvider.request_new_actor( 'vehicle.diamondback.century', second_actor_transform) first_actor.set_simulate_physics(enabled=False) second_actor.set_simulate_physics(enabled=False) self.other_actors.append(first_actor) self.other_actors.append(second_actor) def _create_behavior(self): """ The scenario defined after is a "follow leading vehicle" scenario. After invoking this scenario, it will wait for the user controlled vehicle to enter the start region, then make the other actor to drive towards obstacle. Once obstacle clears the road, make the other actor to drive towards the next intersection. Finally, the user-controlled vehicle has to be close enough to the other actor to end the scenario. If this does not happen within 60 seconds, a timeout stops the scenario """ # let the other actor drive until next intersection driving_to_next_intersection = py_trees.composites.Parallel( "Driving towards Intersection", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) obstacle_clear_road = py_trees.composites.Parallel("Obstalce clearing road", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) obstacle_clear_road.add_child(DriveDistance(self.other_actors[1], 4)) obstacle_clear_road.add_child(KeepVelocity(self.other_actors[1], self._second_actor_speed)) stop_near_intersection = py_trees.composites.Parallel( "Waiting for end position near Intersection", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) stop_near_intersection.add_child(WaypointFollower(self.other_actors[0], 10)) stop_near_intersection.add_child(InTriggerDistanceToNextIntersection(self.other_actors[0], 20)) driving_to_next_intersection.add_child(WaypointFollower(self.other_actors[0], self._first_actor_speed)) driving_to_next_intersection.add_child(InTriggerDistanceToVehicle(self.other_actors[1], self.other_actors[0], 15)) # end condition endcondition = py_trees.composites.Parallel("Waiting for end position", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL) endcondition_part1 = InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], distance=20, name="FinalDistance") endcondition_part2 = StandStill(self.ego_vehicles[0], name="FinalSpeed", duration=1) endcondition.add_child(endcondition_part1) endcondition.add_child(endcondition_part2) # Build behavior tree sequence = py_trees.composites.Sequence("Sequence Behavior") sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform)) sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform)) sequence.add_child(driving_to_next_intersection) sequence.add_child(StopVehicle(self.other_actors[0], self._other_actor_max_brake)) sequence.add_child(TimeOut(3)) sequence.add_child(obstacle_clear_road) sequence.add_child(stop_near_intersection) sequence.add_child(StopVehicle(self.other_actors[0], self._other_actor_max_brake)) sequence.add_child(endcondition) sequence.add_child(ActorDestroy(self.other_actors[0])) sequence.add_child(ActorDestroy(self.other_actors[1])) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/freeride.py ================================================ #!/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 . """ Simple freeride scenario. No action, no triggers. Ego vehicle can simply cruise around. """ import py_trees from srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenarios.basic_scenario import BasicScenario class FreeRide(BasicScenario): """ Implementation of a simple free ride scenario that consits only of the ego vehicle """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=10000000): """ Setup all relevant parameters and create scenario """ # Timeout of scenario in seconds self.timeout = timeout super(FreeRide, self).__init__("FreeRide", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _setup_scenario_trigger(self, config): """ """ return None def _create_behavior(self): """ """ sequence = py_trees.composites.Sequence("Sequence Behavior") sequence.add_child(Idle()) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] for ego_vehicle in self.ego_vehicles: collision_criterion = CollisionTest(ego_vehicle) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/junction_crossing_route.py ================================================ #!/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 . """ All intersection related scenarios that are part of a route. """ from __future__ import print_function import py_trees from srunner.scenariomanager.scenarioatomics.atomic_behaviors import TrafficLightManipulator from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, DrivenDistanceTest, MaxVelocityTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance, WaitEndIntersection from srunner.scenarios.basic_scenario import BasicScenario class SignalJunctionCrossingRoute(BasicScenario): """ At routes, these scenarios are simplified, as they can be triggered making use of the background activity. To ensure interactions with this background activity, the traffic lights are modified, setting two of them to green """ # ego vehicle parameters _ego_max_velocity_allowed = 20 # Maximum allowed velocity [m/s] _ego_expected_driven_distance = 50 # Expected driven distance [m] _ego_distance_to_drive = 20 # Allowed distance to drive _traffic_light = None # Depending on the route, decide which traffic lights can be modified def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): """ Setup all relevant parameters and create scenario and instantiate scenario manager """ # Timeout of scenario in seconds self.timeout = timeout self.subtype = config.subtype super(SignalJunctionCrossingRoute, self).__init__("SignalJunctionCrossingRoute", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ def _create_behavior(self): """ Scenario behavior: When close to an intersection, the traffic lights will turn green for both the ego_vehicle and another lane, allowing the background activity to "run" their red light, creating scenarios 7, 8 and 9. If this does not happen within 120 seconds, a timeout stops the scenario """ # Changes traffic lights traffic_hack = TrafficLightManipulator(self.ego_vehicles[0], self.subtype) # finally wait that ego vehicle drove a specific distance wait = DriveDistance( self.ego_vehicles[0], self._ego_distance_to_drive, name="DriveDistance") # Build behavior tree sequence = py_trees.composites.Sequence("SignalJunctionCrossingRoute") sequence.add_child(traffic_hack) sequence.add_child(wait) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] max_velocity_criterion = MaxVelocityTest( self.ego_vehicles[0], self._ego_max_velocity_allowed, optional=True) collision_criterion = CollisionTest(self.ego_vehicles[0]) driven_distance_criterion = DrivenDistanceTest( self.ego_vehicles[0], self._ego_expected_driven_distance) criteria.append(max_velocity_criterion) criteria.append(collision_criterion) criteria.append(driven_distance_criterion) return criteria def __del__(self): """ Remove all actors and traffic lights upon deletion """ self._traffic_light = None self.remove_all_actors() class NoSignalJunctionCrossingRoute(BasicScenario): """ At routes, these scenarios are simplified, as they can be triggered making use of the background activity. For unsignalized intersections, just wait until the ego_vehicle has left the intersection. """ # ego vehicle parameters _ego_max_velocity_allowed = 20 # Maximum allowed velocity [m/s] _ego_expected_driven_distance = 50 # Expected driven distance [m] _ego_distance_to_drive = 20 # Allowed distance to drive def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): """ Setup all relevant parameters and create scenario and instantiate scenario manager """ # Timeout of scenario in seconds self.timeout = timeout super(NoSignalJunctionCrossingRoute, self).__init__("NoSignalJunctionCrossingRoute", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ def _create_behavior(self): """ Scenario behavior: When close to an intersection, the traffic lights will turn green for both the ego_vehicle and another lane, allowing the background activity to "run" their red light. If this does not happen within 120 seconds, a timeout stops the scenario """ # finally wait that ego vehicle drove a specific distance wait = WaitEndIntersection( self.ego_vehicles[0], name="WaitEndIntersection") end_condition = DriveDistance( self.ego_vehicles[0], self._ego_distance_to_drive, name="DriveDistance") # Build behavior tree sequence = py_trees.composites.Sequence("NoSignalJunctionCrossingRoute") sequence.add_child(wait) sequence.add_child(end_condition) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] max_velocity_criterion = MaxVelocityTest( self.ego_vehicles[0], self._ego_max_velocity_allowed, optional=True) collision_criterion = CollisionTest(self.ego_vehicles[0]) driven_distance_criterion = DrivenDistanceTest( self.ego_vehicles[0], self._ego_expected_driven_distance) criteria.append(max_velocity_criterion) criteria.append(collision_criterion) criteria.append(driven_distance_criterion) return criteria def __del__(self): """ Remove all actors and traffic lights upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/maneuver_opposite_direction.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ Vehicle Maneuvering In Opposite Direction: Vehicle is passing another vehicle in a rural area, in daylight, under clear weather conditions, at a non-junction and encroaches into another vehicle traveling in the opposite direction. """ from six.moves.queue import Queue # pylint: disable=relative-import import math import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, ActorSource, ActorSink, WaypointFollower) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import get_waypoint_in_distance class ManeuverOppositeDirection(BasicScenario): """ "Vehicle Maneuvering In Opposite Direction" (Traffic Scenario 06) This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, obstacle_type='barrier', timeout=120): """ Setup all relevant parameters and create scenario obstacle_type -> flag to select type of leading obstacle. Values: vehicle, barrier """ self._world = world self._map = CarlaDataProvider.get_map() self._first_vehicle_location = 50 self._second_vehicle_location = self._first_vehicle_location + 60 self._ego_vehicle_drive_distance = self._second_vehicle_location * 2 self._start_distance = self._first_vehicle_location * 0.9 self._opposite_speed = 5.56 # m/s self._source_gap = 40 # m self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self._source_transform = None self._sink_location = None self._blackboard_queue_name = 'ManeuverOppositeDirection/actor_flow_queue' self._queue = py_trees.blackboard.Blackboard().set(self._blackboard_queue_name, Queue()) self._obstacle_type = obstacle_type self._first_actor_transform = None self._second_actor_transform = None self._third_actor_transform = None # Timeout of scenario in seconds self.timeout = timeout super(ManeuverOppositeDirection, self).__init__( "ManeuverOppositeDirection", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ first_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location) second_actor_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_vehicle_location) second_actor_waypoint = second_actor_waypoint.get_left_lane() first_actor_transform = carla.Transform( first_actor_waypoint.transform.location, first_actor_waypoint.transform.rotation) if self._obstacle_type == 'vehicle': first_actor_model = 'vehicle.nissan.micra' else: first_actor_transform.rotation.yaw += 90 first_actor_model = 'static.prop.streetbarrier' second_prop_waypoint = first_actor_waypoint.next(2.0)[0] position_yaw = second_prop_waypoint.transform.rotation.yaw + 90 offset_location = carla.Location( 0.50 * second_prop_waypoint.lane_width * math.cos(math.radians(position_yaw)), 0.50 * second_prop_waypoint.lane_width * math.sin(math.radians(position_yaw))) second_prop_transform = carla.Transform( second_prop_waypoint.transform.location + offset_location, first_actor_transform.rotation) second_prop_actor = CarlaDataProvider.request_new_actor(first_actor_model, second_prop_transform) second_prop_actor.set_simulate_physics(True) first_actor = CarlaDataProvider.request_new_actor(first_actor_model, first_actor_transform) first_actor.set_simulate_physics(True) second_actor = CarlaDataProvider.request_new_actor('vehicle.audi.tt', second_actor_waypoint.transform) self.other_actors.append(first_actor) self.other_actors.append(second_actor) if self._obstacle_type != 'vehicle': self.other_actors.append(second_prop_actor) self._source_transform = second_actor_waypoint.transform sink_waypoint = second_actor_waypoint.next(1)[0] while not sink_waypoint.is_intersection: sink_waypoint = sink_waypoint.next(1)[0] self._sink_location = sink_waypoint.transform.location self._first_actor_transform = first_actor_transform self._second_actor_transform = second_actor_waypoint.transform self._third_actor_transform = second_prop_transform def _create_behavior(self): """ The behavior tree returned by this method is as follows: The ego vehicle is trying to pass a leading vehicle in the same lane by moving onto the oncoming lane while another vehicle is moving in the opposite direction in the oncoming lane. """ # Leaf nodes actor_source = ActorSource( ['vehicle.audi.tt', 'vehicle.tesla.model3', 'vehicle.nissan.micra'], self._source_transform, self._source_gap, self._blackboard_queue_name) actor_sink = ActorSink(self._sink_location, 10) ego_drive_distance = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_drive_distance) waypoint_follower = WaypointFollower( self.other_actors[1], self._opposite_speed, blackboard_queue_name=self._blackboard_queue_name, avoid_collision=True) # Non-leaf nodes parallel_root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) # Building tree parallel_root.add_child(ego_drive_distance) parallel_root.add_child(actor_source) parallel_root.add_child(actor_sink) parallel_root.add_child(waypoint_follower) scenario_sequence = py_trees.composites.Sequence() scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform)) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform)) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[2], self._third_actor_transform)) scenario_sequence.add_child(parallel_root) scenario_sequence.add_child(ActorDestroy(self.other_actors[0])) scenario_sequence.add_child(ActorDestroy(self.other_actors[1])) scenario_sequence.add_child(ActorDestroy(self.other_actors[2])) return scenario_sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/master_scenario.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Basic CARLA Autonomous Driving training scenario """ import py_trees from srunner.scenarioconfigs.route_scenario_configuration import RouteConfiguration from srunner.scenariomanager.scenarioatomics.atomic_behaviors import Idle from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, InRouteTest, RouteCompletionTest, OutsideRouteLanesTest, RunningRedLightTest, RunningStopTest, ActorSpeedAboveThresholdTest) from srunner.scenarios.basic_scenario import BasicScenario class MasterScenario(BasicScenario): """ Implementation of a Master scenario that controls the route. This is a single ego vehicle scenario """ radius = 10.0 # meters def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=300): """ Setup all relevant parameters and create scenario """ self.config = config self.route = None # Timeout of scenario in seconds self.timeout = timeout if hasattr(self.config, 'route'): self.route = self.config.route else: raise ValueError("Master scenario must have a route") super(MasterScenario, self).__init__("MasterScenario", ego_vehicles=ego_vehicles, config=config, world=world, debug_mode=debug_mode, terminate_on_failure=True, criteria_enable=criteria_enable) def _create_behavior(self): """ Basic behavior do nothing, i.e. Idle """ # Build behavior tree sequence = py_trees.composites.Sequence("MasterScenario") idle_behavior = Idle() sequence.add_child(idle_behavior) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ if isinstance(self.route, RouteConfiguration): route = self.route.data else: route = 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) parallel_criteria = py_trees.composites.Parallel("group_criteria", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) parallel_criteria.add_child(completion_criterion) parallel_criteria.add_child(collision_criterion) parallel_criteria.add_child(route_criterion) parallel_criteria.add_child(outsidelane_criterion) parallel_criteria.add_child(red_light_criterion) parallel_criteria.add_child(stop_criterion) parallel_criteria.add_child(blocked_criterion) return parallel_criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/no_signal_junction_crossing.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Non-signalized junctions: crossing negotiation: The hero vehicle is passing through a junction without traffic lights And encounters another vehicle passing across the junction. """ import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, SyncArrival, KeepVelocity, StopVehicle) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerRegion from srunner.scenarios.basic_scenario import BasicScenario class NoSignalJunctionCrossing(BasicScenario): """ Implementation class for 'Non-signalized junctions: crossing negotiation' scenario, (Traffic Scenario 10). This is a single ego vehicle scenario """ # ego vehicle parameters _ego_vehicle_max_velocity = 20 _ego_vehicle_driven_distance = 105 # other vehicle _other_actor_max_brake = 1.0 _other_actor_target_velocity = 15 def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario """ self._other_actor_transform = None # Timeout of scenario in seconds self.timeout = timeout super(NoSignalJunctionCrossing, self).__init__("NoSignalJunctionCrossing", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ self._other_actor_transform = config.other_actors[0].transform first_vehicle_transform = carla.Transform( carla.Location(config.other_actors[0].transform.location.x, config.other_actors[0].transform.location.y, config.other_actors[0].transform.location.z - 500), config.other_actors[0].transform.rotation) first_vehicle = CarlaDataProvider.request_new_actor(config.other_actors[0].model, first_vehicle_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ After invoking this scenario, it will wait for the user controlled vehicle to enter the start region, then make a traffic participant to accelerate until it is going fast enough to reach an intersection point. at the same time as the user controlled vehicle at the junction. Once the user controlled vehicle comes close to the junction, the traffic participant accelerates and passes through the junction. After 60 seconds, a timeout stops the scenario. """ # Creating leaf nodes start_other_trigger = InTriggerRegion( self.ego_vehicles[0], -80, -70, -75, -60) sync_arrival = SyncArrival( self.other_actors[0], self.ego_vehicles[0], carla.Location(x=-74.63, y=-136.34)) pass_through_trigger = InTriggerRegion( self.ego_vehicles[0], -90, -70, -124, -119) keep_velocity_other = KeepVelocity( self.other_actors[0], self._other_actor_target_velocity) stop_other_trigger = InTriggerRegion( self.other_actors[0], -45, -35, -140, -130) stop_other = StopVehicle( self.other_actors[0], self._other_actor_max_brake) end_condition = InTriggerRegion( self.ego_vehicles[0], -90, -70, -170, -156 ) # Creating non-leaf nodes root = py_trees.composites.Sequence() scenario_sequence = py_trees.composites.Sequence() sync_arrival_parallel = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) keep_velocity_other_parallel = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) # Building tree root.add_child(scenario_sequence) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform)) scenario_sequence.add_child(start_other_trigger) scenario_sequence.add_child(sync_arrival_parallel) scenario_sequence.add_child(keep_velocity_other_parallel) scenario_sequence.add_child(stop_other) scenario_sequence.add_child(end_condition) scenario_sequence.add_child(ActorDestroy(self.other_actors[0])) sync_arrival_parallel.add_child(sync_arrival) sync_arrival_parallel.add_child(pass_through_trigger) keep_velocity_other_parallel.add_child(keep_velocity_other) keep_velocity_other_parallel.add_child(stop_other_trigger) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collison_criteria = CollisionTest(self.ego_vehicles[0]) criteria.append(collison_criteria) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/object_crash_intersection.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Object crash with prior vehicle action scenario: The scenario realizes the user controlled ego vehicle moving along the road and encounters a cyclist ahead after taking a right or left turn. """ from __future__ import print_function import math import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, KeepVelocity, HandBrakeVehicle) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocationAlongRoute, InTriggerDistanceToVehicle, DriveDistance) from srunner.scenariomanager.timer import TimeOut from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import generate_target_waypoint, generate_target_waypoint_in_route def get_opponent_transform(added_dist, waypoint, trigger_location): """ Calculate the transform of the adversary """ lane_width = waypoint.lane_width offset = {"orientation": 270, "position": 90, "k": 1.0} _wp = waypoint.next(added_dist) if _wp: _wp = _wp[-1] else: raise RuntimeError("Cannot get next waypoint !") location = _wp.transform.location orientation_yaw = _wp.transform.rotation.yaw + offset["orientation"] position_yaw = _wp.transform.rotation.yaw + offset["position"] offset_location = carla.Location( offset['k'] * lane_width * math.cos(math.radians(position_yaw)), offset['k'] * lane_width * math.sin(math.radians(position_yaw))) location += offset_location location.z = trigger_location.z transform = carla.Transform(location, carla.Rotation(yaw=orientation_yaw)) return transform def get_right_driving_lane(waypoint): """ Gets the driving / parking lane that is most to the right of the waypoint as well as the number of lane changes done """ lane_changes = 0 while True: wp_next = waypoint.get_right_lane() lane_changes += 1 if wp_next is None or wp_next.lane_type == carla.LaneType.Sidewalk: break elif wp_next.lane_type == carla.LaneType.Shoulder: # Filter Parkings considered as Shoulders if is_lane_a_parking(wp_next): lane_changes += 1 waypoint = wp_next break else: waypoint = wp_next return waypoint, lane_changes def is_lane_a_parking(waypoint): """ This function filters false negative Shoulder which are in reality Parking lanes. These are differentiated from the others because, similar to the driving lanes, they have, on the right, a small Shoulder followed by a Sidewalk. """ # Parking are wide lanes if waypoint.lane_width > 2: wp_next = waypoint.get_right_lane() # That are next to a mini-Shoulder if wp_next is not None and wp_next.lane_type == carla.LaneType.Shoulder: wp_next_next = wp_next.get_right_lane() # Followed by a Sidewalk if wp_next_next is not None and wp_next_next.lane_type == carla.LaneType.Sidewalk: return True return False class VehicleTurningRight(BasicScenario): """ This class holds everything required for a simple object crash with prior vehicle action involving a vehicle and a cyclist. The ego vehicle is passing through a road and encounters a cyclist after taking a right turn. (Traffic Scenario 4) This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario """ self._other_actor_target_velocity = 10 self._wmap = CarlaDataProvider.get_map() self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location) self._trigger_location = config.trigger_points[0].location self._other_actor_transform = None self._num_lane_changes = 0 # Timeout of scenario in seconds self.timeout = timeout # Total Number of attempts to relocate a vehicle before spawning self._number_of_attempts = 6 # Number of attempts made so far self._spawn_attempted = 0 self._ego_route = CarlaDataProvider.get_ego_vehicle_route() super(VehicleTurningRight, self).__init__("VehicleTurningRight", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ # Get the waypoint right after the junction waypoint = generate_target_waypoint(self._reference_waypoint, 1) # Move a certain distance to the front start_distance = 8 waypoint = waypoint.next(start_distance)[0] # Get the last driving lane to the right waypoint, self._num_lane_changes = get_right_driving_lane(waypoint) # And for synchrony purposes, move to the front a bit added_dist = self._num_lane_changes while True: # Try to spawn the actor try: self._other_actor_transform = get_opponent_transform(added_dist, waypoint, self._trigger_location) first_vehicle = CarlaDataProvider.request_new_actor( 'vehicle.diamondback.century', self._other_actor_transform) first_vehicle.set_simulate_physics(enabled=False) break # Move the spawning point a bit and try again except RuntimeError as r: # In the case there is an object just move a little bit and retry print(" Base transform is blocking objects ", self._other_actor_transform) added_dist += 0.5 self._spawn_attempted += 1 if self._spawn_attempted >= self._number_of_attempts: raise r # Set the transform to -500 z after we are able to spawn it actor_transform = carla.Transform( carla.Location(self._other_actor_transform.location.x, self._other_actor_transform.location.y, self._other_actor_transform.location.z - 500), self._other_actor_transform.rotation) first_vehicle.set_transform(actor_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ After invoking this scenario, cyclist will wait for the user controlled vehicle to enter the in the trigger distance region, the cyclist starts crossing the road once the condition meets, ego vehicle has to avoid the crash after a right turn, but continue driving after the road is clear.If this does not happen within 90 seconds, a timeout stops the scenario. """ root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="IntersectionRightTurn") lane_width = self._reference_waypoint.lane_width dist_to_travel = lane_width + (1.10 * lane_width * self._num_lane_changes) bycicle_start_dist = 13 + dist_to_travel if self._ego_route is not None: trigger_distance = InTriggerDistanceToLocationAlongRoute(self.ego_vehicles[0], self._ego_route, self._other_actor_transform.location, bycicle_start_dist) else: trigger_distance = InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], bycicle_start_dist) actor_velocity = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity) actor_traverse = DriveDistance(self.other_actors[0], 0.30 * dist_to_travel) post_timer_velocity_actor = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity) post_timer_traverse_actor = DriveDistance(self.other_actors[0], 0.70 * dist_to_travel) end_condition = TimeOut(5) # non leaf nodes scenario_sequence = py_trees.composites.Sequence() actor_ego_sync = py_trees.composites.Parallel( "Synchronization of actor and ego vehicle", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) after_timer_actor = py_trees.composites.Parallel( "After timeout actor will cross the remaining lane_width", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) # building the tree root.add_child(scenario_sequence) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform, name='TransformSetterTS4')) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], True)) scenario_sequence.add_child(trigger_distance) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], False)) scenario_sequence.add_child(actor_ego_sync) scenario_sequence.add_child(after_timer_actor) scenario_sequence.add_child(end_condition) scenario_sequence.add_child(ActorDestroy(self.other_actors[0])) actor_ego_sync.add_child(actor_velocity) actor_ego_sync.add_child(actor_traverse) after_timer_actor.add_child(post_timer_velocity_actor) after_timer_actor.add_child(post_timer_traverse_actor) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() class VehicleTurningLeft(BasicScenario): """ This class holds everything required for a simple object crash with prior vehicle action involving a vehicle and a cyclist. The ego vehicle is passing through a road and encounters a cyclist after taking a left turn. (Traffic Scenario 4) This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario """ self._other_actor_target_velocity = 10 self._wmap = CarlaDataProvider.get_map() self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location) self._trigger_location = config.trigger_points[0].location self._other_actor_transform = None self._num_lane_changes = 0 # Timeout of scenario in seconds self.timeout = timeout # Total Number of attempts to relocate a vehicle before spawning self._number_of_attempts = 6 # Number of attempts made so far self._spawn_attempted = 0 self._ego_route = CarlaDataProvider.get_ego_vehicle_route() super(VehicleTurningLeft, self).__init__("VehicleTurningLeft", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ # Get the waypoint right after the junction waypoint = generate_target_waypoint(self._reference_waypoint, -1) # Move a certain distance to the front start_distance = 8 waypoint = waypoint.next(start_distance)[0] # Get the last driving lane to the right waypoint, self._num_lane_changes = get_right_driving_lane(waypoint) # And for synchrony purposes, move to the front a bit added_dist = self._num_lane_changes while True: # Try to spawn the actor try: self._other_actor_transform = get_opponent_transform(added_dist, waypoint, self._trigger_location) first_vehicle = CarlaDataProvider.request_new_actor( 'vehicle.diamondback.century', self._other_actor_transform) first_vehicle.set_simulate_physics(enabled=False) break # Move the spawning point a bit and try again except RuntimeError as r: # In the case there is an object just move a little bit and retry print(" Base transform is blocking objects ", self._other_actor_transform) added_dist += 0.5 self._spawn_attempted += 1 if self._spawn_attempted >= self._number_of_attempts: raise r # Set the transform to -500 z after we are able to spawn it actor_transform = carla.Transform( carla.Location(self._other_actor_transform.location.x, self._other_actor_transform.location.y, self._other_actor_transform.location.z - 500), self._other_actor_transform.rotation) first_vehicle.set_transform(actor_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ After invoking this scenario, cyclist will wait for the user controlled vehicle to enter the in the trigger distance region, the cyclist starts crossing the road once the condition meets, ego vehicle has to avoid the crash after a left turn, but continue driving after the road is clear.If this does not happen within 90 seconds, a timeout stops the scenario. """ root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="IntersectionLeftTurn") lane_width = self._reference_waypoint.lane_width dist_to_travel = lane_width + (1.10 * lane_width * self._num_lane_changes) bycicle_start_dist = 13 + dist_to_travel if self._ego_route is not None: trigger_distance = InTriggerDistanceToLocationAlongRoute(self.ego_vehicles[0], self._ego_route, self._other_actor_transform.location, bycicle_start_dist) else: trigger_distance = InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], bycicle_start_dist) actor_velocity = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity) actor_traverse = DriveDistance(self.other_actors[0], 0.30 * dist_to_travel) post_timer_velocity_actor = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity) post_timer_traverse_actor = DriveDistance(self.other_actors[0], 0.70 * dist_to_travel) end_condition = TimeOut(5) # non leaf nodes scenario_sequence = py_trees.composites.Sequence() actor_ego_sync = py_trees.composites.Parallel( "Synchronization of actor and ego vehicle", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) after_timer_actor = py_trees.composites.Parallel( "After timeout actor will cross the remaining lane_width", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) # building the tree root.add_child(scenario_sequence) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform, name='TransformSetterTS4')) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], True)) scenario_sequence.add_child(trigger_distance) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], False)) scenario_sequence.add_child(actor_ego_sync) scenario_sequence.add_child(after_timer_actor) scenario_sequence.add_child(end_condition) scenario_sequence.add_child(ActorDestroy(self.other_actors[0])) actor_ego_sync.add_child(actor_velocity) actor_ego_sync.add_child(actor_traverse) after_timer_actor.add_child(post_timer_velocity_actor) after_timer_actor.add_child(post_timer_traverse_actor) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() class VehicleTurningRoute(BasicScenario): """ This class holds everything required for a simple object crash with prior vehicle action involving a vehicle and a cyclist. The ego vehicle is passing through a road and encounters a cyclist after taking a turn. This is the version used when the ego vehicle is following a given route. (Traffic Scenario 4) This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario """ self._other_actor_target_velocity = 10 self._wmap = CarlaDataProvider.get_map() self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location) self._trigger_location = config.trigger_points[0].location self._other_actor_transform = None self._num_lane_changes = 0 # Timeout of scenario in seconds self.timeout = timeout # Total Number of attempts to relocate a vehicle before spawning self._number_of_attempts = 6 # Number of attempts made so far self._spawn_attempted = 0 self._ego_route = CarlaDataProvider.get_ego_vehicle_route() super(VehicleTurningRoute, self).__init__("VehicleTurningRoute", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ # Get the waypoint right after the junction waypoint = generate_target_waypoint_in_route(self._reference_waypoint, self._ego_route) # Move a certain distance to the front start_distance = 8 waypoint = waypoint.next(start_distance)[0] # Get the last driving lane to the right waypoint, self._num_lane_changes = get_right_driving_lane(waypoint) # And for synchrony purposes, move to the front a bit added_dist = self._num_lane_changes while True: # Try to spawn the actor try: self._other_actor_transform = get_opponent_transform(added_dist, waypoint, self._trigger_location) first_vehicle = CarlaDataProvider.request_new_actor( 'vehicle.diamondback.century', self._other_actor_transform) first_vehicle.set_simulate_physics(enabled=False) break # Move the spawning point a bit and try again except RuntimeError as r: # In the case there is an object just move a little bit and retry print(" Base transform is blocking objects ", self._other_actor_transform) added_dist += 0.5 self._spawn_attempted += 1 if self._spawn_attempted >= self._number_of_attempts: raise r # Set the transform to -500 z after we are able to spawn it actor_transform = carla.Transform( carla.Location(self._other_actor_transform.location.x, self._other_actor_transform.location.y, self._other_actor_transform.location.z - 500), self._other_actor_transform.rotation) first_vehicle.set_transform(actor_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ After invoking this scenario, cyclist will wait for the user controlled vehicle to enter the in the trigger distance region, the cyclist starts crossing the road once the condition meets, ego vehicle has to avoid the crash after a turn, but continue driving after the road is clear.If this does not happen within 90 seconds, a timeout stops the scenario. """ root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="IntersectionRouteTurn") lane_width = self._reference_waypoint.lane_width dist_to_travel = lane_width + (1.10 * lane_width * self._num_lane_changes) bycicle_start_dist = 13 + dist_to_travel if self._ego_route is not None: trigger_distance = InTriggerDistanceToLocationAlongRoute(self.ego_vehicles[0], self._ego_route, self._other_actor_transform.location, bycicle_start_dist) else: trigger_distance = InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], bycicle_start_dist) actor_velocity = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity) actor_traverse = DriveDistance(self.other_actors[0], 0.30 * dist_to_travel) post_timer_velocity_actor = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity) post_timer_traverse_actor = DriveDistance(self.other_actors[0], 0.70 * dist_to_travel) end_condition = TimeOut(5) # non leaf nodes scenario_sequence = py_trees.composites.Sequence() actor_ego_sync = py_trees.composites.Parallel( "Synchronization of actor and ego vehicle", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) after_timer_actor = py_trees.composites.Parallel( "After timeout actor will cross the remaining lane_width", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) # building the tree root.add_child(scenario_sequence) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform, name='TransformSetterTS4')) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], True)) scenario_sequence.add_child(trigger_distance) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], False)) scenario_sequence.add_child(actor_ego_sync) scenario_sequence.add_child(after_timer_actor) scenario_sequence.add_child(end_condition) scenario_sequence.add_child(ActorDestroy(self.other_actors[0])) actor_ego_sync.add_child(actor_velocity) actor_ego_sync.add_child(actor_traverse) after_timer_actor.add_child(post_timer_velocity_actor) after_timer_actor.add_child(post_timer_traverse_actor) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/object_crash_vehicle.py ================================================ #!/usr/bin/env python # This work is licensed under the terms of the MIT license. # For a copy, see . """ Object crash without prior vehicle action scenario: The scenario realizes the user controlled ego vehicle moving along the road and encountering a cyclist ahead. """ from __future__ import print_function import math import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, AccelerateToVelocity, HandBrakeVehicle, KeepVelocity, StopVehicle) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocationAlongRoute, InTimeToArrivalToVehicle, DriveDistance) from srunner.scenariomanager.timer import TimeOut from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import get_location_in_distance_from_wp class StationaryObjectCrossing(BasicScenario): """ This class holds everything required for a simple object crash without prior vehicle action involving a vehicle and a cyclist. The ego vehicle is passing through a road and encounters a stationary cyclist. This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): """ Setup all relevant parameters and create scenario """ self._wmap = CarlaDataProvider.get_map() self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location) # ego vehicle parameters self._ego_vehicle_distance_driven = 40 # other vehicle parameters self._other_actor_target_velocity = 10 # Timeout of scenario in seconds self.timeout = timeout super(StationaryObjectCrossing, self).__init__("Stationaryobjectcrossing", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ _start_distance = 40 lane_width = self._reference_waypoint.lane_width location, _ = get_location_in_distance_from_wp(self._reference_waypoint, _start_distance) waypoint = self._wmap.get_waypoint(location) offset = {"orientation": 270, "position": 90, "z": 0.4, "k": 0.2} position_yaw = waypoint.transform.rotation.yaw + offset['position'] orientation_yaw = waypoint.transform.rotation.yaw + offset['orientation'] offset_location = carla.Location( offset['k'] * lane_width * math.cos(math.radians(position_yaw)), offset['k'] * lane_width * math.sin(math.radians(position_yaw))) location += offset_location location.z += offset['z'] self.transform = carla.Transform(location, carla.Rotation(yaw=orientation_yaw)) static = CarlaDataProvider.request_new_actor('static.prop.container', self.transform) static.set_simulate_physics(True) self.other_actors.append(static) def _create_behavior(self): """ Only behavior here is to wait """ lane_width = self.ego_vehicles[0].get_world().get_map().get_waypoint( self.ego_vehicles[0].get_location()).lane_width lane_width = lane_width + (1.25 * lane_width) # leaf nodes actor_stand = TimeOut(15) actor_removed = ActorDestroy(self.other_actors[0]) end_condition = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_distance_driven) # non leaf nodes root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) scenario_sequence = py_trees.composites.Sequence() # building tree root.add_child(scenario_sequence) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self.transform)) scenario_sequence.add_child(actor_stand) scenario_sequence.add_child(actor_removed) scenario_sequence.add_child(end_condition) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() class DynamicObjectCrossing(BasicScenario): """ This class holds everything required for a simple object crash without prior vehicle action involving a vehicle and a cyclist/pedestrian, The ego vehicle is passing through a road, And encounters a cyclist/pedestrian crossing the road. This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, adversary_type=False, timeout=60): """ Setup all relevant parameters and create scenario """ self._wmap = CarlaDataProvider.get_map() self._reference_waypoint = self._wmap.get_waypoint(config.trigger_points[0].location) # ego vehicle parameters self._ego_vehicle_distance_driven = 40 # other vehicle parameters self._other_actor_target_velocity = 5 self._other_actor_max_brake = 1.0 self._time_to_reach = 10 self._adversary_type = adversary_type # flag to select either pedestrian (False) or cyclist (True) self._walker_yaw = 0 self._num_lane_changes = 1 self.transform = None self.transform2 = None self.timeout = timeout self._trigger_location = config.trigger_points[0].location # Total Number of attempts to relocate a vehicle before spawning self._number_of_attempts = 20 # Number of attempts made so far self._spawn_attempted = 0 self._ego_route = CarlaDataProvider.get_ego_vehicle_route() super(DynamicObjectCrossing, self).__init__("DynamicObjectCrossing", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _calculate_base_transform(self, _start_distance, waypoint): lane_width = waypoint.lane_width # Patches false junctions if self._reference_waypoint.is_junction: stop_at_junction = False else: stop_at_junction = True location, _ = get_location_in_distance_from_wp(waypoint, _start_distance, stop_at_junction) waypoint = self._wmap.get_waypoint(location) offset = {"orientation": 270, "position": 90, "z": 0.6, "k": 1.0} position_yaw = waypoint.transform.rotation.yaw + offset['position'] orientation_yaw = waypoint.transform.rotation.yaw + offset['orientation'] offset_location = carla.Location( offset['k'] * lane_width * math.cos(math.radians(position_yaw)), offset['k'] * lane_width * math.sin(math.radians(position_yaw))) location += offset_location location.z = self._trigger_location.z + offset['z'] return carla.Transform(location, carla.Rotation(yaw=orientation_yaw)), orientation_yaw def _spawn_adversary(self, transform, orientation_yaw): self._time_to_reach *= self._num_lane_changes if self._adversary_type is False: self._walker_yaw = orientation_yaw self._other_actor_target_velocity = 3 + (0.4 * self._num_lane_changes) walker = CarlaDataProvider.request_new_actor('walker.*', transform) adversary = walker else: self._other_actor_target_velocity = self._other_actor_target_velocity * self._num_lane_changes first_vehicle = CarlaDataProvider.request_new_actor('vehicle.diamondback.century', transform) first_vehicle.set_simulate_physics(enabled=False) adversary = first_vehicle return adversary def _spawn_blocker(self, transform, orientation_yaw): """ Spawn the blocker prop that blocks the vision from the egovehicle of the jaywalker :return: """ # static object transform shift = 0.9 x_ego = self._reference_waypoint.transform.location.x y_ego = self._reference_waypoint.transform.location.y x_cycle = transform.location.x y_cycle = transform.location.y x_static = x_ego + shift * (x_cycle - x_ego) y_static = y_ego + shift * (y_cycle - y_ego) spawn_point_wp = self.ego_vehicles[0].get_world().get_map().get_waypoint(transform.location) self.transform2 = carla.Transform(carla.Location(x_static, y_static, spawn_point_wp.transform.location.z + 0.3), carla.Rotation(yaw=orientation_yaw + 180)) static = CarlaDataProvider.request_new_actor('static.prop.vendingmachine', self.transform2) static.set_simulate_physics(enabled=False) return static def _initialize_actors(self, config): """ Custom initialization """ # cyclist transform _start_distance = 12 # We start by getting and waypoint in the closest sidewalk. waypoint = self._reference_waypoint while True: wp_next = waypoint.get_right_lane() self._num_lane_changes += 1 if wp_next is None or wp_next.lane_type == carla.LaneType.Sidewalk: break elif wp_next.lane_type == carla.LaneType.Shoulder: # Filter Parkings considered as Shoulders if wp_next.lane_width > 2: _start_distance += 1.5 waypoint = wp_next break else: _start_distance += 1.5 waypoint = wp_next while True: # We keep trying to spawn avoiding props try: self.transform, orientation_yaw = self._calculate_base_transform(_start_distance, waypoint) first_vehicle = self._spawn_adversary(self.transform, orientation_yaw) blocker = self._spawn_blocker(self.transform, orientation_yaw) break except RuntimeError as r: # We keep retrying until we spawn print("Base transform is blocking objects ", self.transform) _start_distance += 0.4 self._spawn_attempted += 1 if self._spawn_attempted >= self._number_of_attempts: raise r # Now that we found a possible position we just put the vehicle to the underground disp_transform = carla.Transform( carla.Location(self.transform.location.x, self.transform.location.y, self.transform.location.z - 500), self.transform.rotation) prop_disp_transform = carla.Transform( carla.Location(self.transform2.location.x, self.transform2.location.y, self.transform2.location.z - 500), self.transform2.rotation) first_vehicle.set_transform(disp_transform) blocker.set_transform(prop_disp_transform) first_vehicle.set_simulate_physics(enabled=False) blocker.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) self.other_actors.append(blocker) def _create_behavior(self): """ After invoking this scenario, cyclist will wait for the user controlled vehicle to enter trigger distance region, the cyclist starts crossing the road once the condition meets, then after 60 seconds, a timeout stops the scenario """ root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="OccludedObjectCrossing") lane_width = self._reference_waypoint.lane_width lane_width = lane_width + (1.25 * lane_width * self._num_lane_changes) dist_to_trigger = 12 + self._num_lane_changes # leaf nodes if self._ego_route is not None: start_condition = InTriggerDistanceToLocationAlongRoute(self.ego_vehicles[0], self._ego_route, self.transform.location, dist_to_trigger) else: start_condition = InTimeToArrivalToVehicle(self.ego_vehicles[0], self.other_actors[0], self._time_to_reach) actor_velocity = KeepVelocity(self.other_actors[0], self._other_actor_target_velocity, name="walker velocity") actor_drive = DriveDistance(self.other_actors[0], 0.5 * lane_width, name="walker drive distance") actor_start_cross_lane = AccelerateToVelocity(self.other_actors[0], 1.0, self._other_actor_target_velocity, name="walker crossing lane accelerate velocity") actor_cross_lane = DriveDistance(self.other_actors[0], lane_width, name="walker drive distance for lane crossing ") actor_stop_crossed_lane = StopVehicle(self.other_actors[0], self._other_actor_max_brake, name="walker stop") ego_pass_machine = DriveDistance(self.ego_vehicles[0], 5, name="ego vehicle passed prop") actor_remove = ActorDestroy(self.other_actors[0], name="Destroying walker") static_remove = ActorDestroy(self.other_actors[1], name="Destroying Prop") end_condition = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_distance_driven, name="End condition ego drive distance") # non leaf nodes scenario_sequence = py_trees.composites.Sequence() keep_velocity_other = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="keep velocity other") keep_velocity = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="keep velocity") # building tree root.add_child(scenario_sequence) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[0], self.transform, name='TransformSetterTS3walker')) scenario_sequence.add_child(ActorTransformSetter(self.other_actors[1], self.transform2, name='TransformSetterTS3coca', physics=False)) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], True)) scenario_sequence.add_child(start_condition) scenario_sequence.add_child(HandBrakeVehicle(self.other_actors[0], False)) scenario_sequence.add_child(keep_velocity) scenario_sequence.add_child(keep_velocity_other) scenario_sequence.add_child(actor_stop_crossed_lane) scenario_sequence.add_child(actor_remove) scenario_sequence.add_child(static_remove) scenario_sequence.add_child(end_condition) keep_velocity.add_child(actor_velocity) keep_velocity.add_child(actor_drive) keep_velocity_other.add_child(actor_start_cross_lane) keep_velocity_other.add_child(actor_cross_lane) keep_velocity_other.add_child(ego_pass_machine) return root def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/open_scenario.py ================================================ #!/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 . """ Basic scenario class using the OpenSCENARIO definition """ from __future__ import print_function import itertools import py_trees from srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeWeather, ChangeRoadFriction from srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeActorControl, ChangeActorTargetSpeed from srunner.scenariomanager.timer import GameTime from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.openscenario_parser import OpenScenarioParser from srunner.tools.py_trees_port import Decorator, oneshot_behavior def repeatable_behavior(behaviour, name=None): """ This behaviour allows a composite with oneshot ancestors to run multiple times, resetting the oneshot variables after each execution """ if not name: name = behaviour.name clear_descendant_variables = ClearBlackboardVariablesStartingWith( name="Clear Descendant Variables of {}".format(name), variable_name_beginning=name + ">" ) # If it's a sequence, don't double-nest it in a redundant manner if isinstance(behaviour, py_trees.composites.Sequence): behaviour.add_child(clear_descendant_variables) sequence = behaviour else: sequence = py_trees.composites.Sequence(name="RepeatableBehaviour of {}".format(name)) sequence.add_children([behaviour, clear_descendant_variables]) return sequence class ClearBlackboardVariablesStartingWith(py_trees.behaviours.Success): """ Clear the values starting with the specified string from the blackboard. Args: name (:obj:`str`): name of the behaviour variable_name_beginning (:obj:`str`): beginning of the names of variable to clear """ def __init__(self, name="Clear Blackboard Variable Starting With", variable_name_beginning="dummy", ): super(ClearBlackboardVariablesStartingWith, self).__init__(name) self.variable_name_beginning = variable_name_beginning def initialise(self): """ Delete the variables from the blackboard. """ blackboard_variables = [key for key, _ in py_trees.blackboard.Blackboard().__dict__.items( ) if key.startswith(self.variable_name_beginning)] for variable in blackboard_variables: delattr(py_trees.blackboard.Blackboard(), variable) class StoryElementStatusToBlackboard(Decorator): """ Reflect the status of the decorator's child story element to the blackboard. Args: child: the child behaviour or subtree story_element_type: the element type [act,scene,maneuver,event,action] element_name: the story element's name attribute """ def __init__(self, child, story_element_type, element_name): super(StoryElementStatusToBlackboard, self).__init__(name=child.name, child=child) self.story_element_type = story_element_type self.element_name = element_name self.blackboard = py_trees.blackboard.Blackboard() def initialise(self): """ Record the elements's start time on the blackboard """ self.blackboard.set( name="({}){}-{}".format(self.story_element_type.upper(), self.element_name, "START"), value=GameTime.get_time(), overwrite=True ) def update(self): """ Reflect the decorated child's status Returns: the decorated child's status """ return self.decorated.status def terminate(self, new_status): """ Terminate and mark Blackboard entry with END """ # Report whether we ended with End or Cancel # If we were ended or cancelled, our state will be INVALID and # We will have an ancestor (a parallel SUCCESS_ON_ALL) with a successful child/children # It's possible we ENDed AND CANCELled if both condition groups were true simultaneously # NOTE 'py_trees.common.Status.INVALID' is the status of a behaviur which was terminated by a parent rules = [] if new_status == py_trees.common.Status.INVALID: # We were terminated from above unnaturally # Figure out if were ended or cancelled terminating_ancestor = self.parent while terminating_ancestor.status == py_trees.common.Status.INVALID: terminating_ancestor = terminating_ancestor.parent # We have found an ancestory which was not terminated by a parent # Check what caused it to terminate its children if terminating_ancestor.status == py_trees.common.Status.SUCCESS: successful_children = [ child.name for child in terminating_ancestor.children if child.status == py_trees.common.Status.SUCCESS] if "StopTrigger" in successful_children: rules.append("END") # END is the default status unless we have a more detailed one rules = rules or ["END"] for rule in rules: self.blackboard.set( name="({}){}-{}".format(self.story_element_type.upper(), self.element_name, rule), value=GameTime.get_time(), overwrite=True ) def get_xml_path(tree, node): """ Extract the full path of a node within an XML tree Note: Catalogs are pulled from a separate file so the XML tree is split. This means that in order to get the XML path, it must be done in 2 steps. Some places in this python script do that by concatenating the results of 2 get_xml_path calls with another ">". Example: "Behavior>AutopilotSequence" + ">" + "StartAutopilot>StartAutopilot>StartAutopilot" """ path = "" parent_map = {c: p for p in tree.iter() for c in p} cur_node = node while cur_node != tree: path = "{}>{}".format(cur_node.attrib.get('name'), path) cur_node = parent_map[cur_node] path = path[:-1] return path class OpenScenario(BasicScenario): """ Implementation of the OpenSCENARIO scenario """ def __init__(self, world, ego_vehicles, config, config_file, debug_mode=False, criteria_enable=True, timeout=300): """ Setup all relevant parameters and create scenario """ self.config = config self.route = None self.config_file = config_file # Timeout of scenario in seconds self.timeout = timeout super(OpenScenario, self).__init__("OpenScenario", ego_vehicles=ego_vehicles, config=config, world=world, debug_mode=debug_mode, terminate_on_failure=False, criteria_enable=criteria_enable) def _initialize_environment(self, world): """ Initialization of weather and road friction. """ pass def _create_environment_behavior(self): # Set the appropriate weather conditions env_behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="EnvironmentBehavior") weather_update = ChangeWeather( OpenScenarioParser.get_weather_from_env_action(self.config.init, self.config.catalogs)) road_friction = ChangeRoadFriction( OpenScenarioParser.get_friction_from_env_action(self.config.init, self.config.catalogs)) env_behavior.add_child(oneshot_behavior(variable_name="InitialWeather", behaviour=weather_update)) env_behavior.add_child(oneshot_behavior(variable_name="InitRoadFriction", behaviour=road_friction)) return env_behavior def _create_init_behavior(self): init_behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="InitBehaviour") for actor in self.config.other_actors + self.config.ego_vehicles: for carla_actor in self.other_actors + self.ego_vehicles: if 'role_name' in carla_actor.attributes and carla_actor.attributes['role_name'] == actor.rolename: actor_init_behavior = py_trees.composites.Sequence(name="InitActor{}".format(actor.rolename)) controller_atomic = None for private in self.config.init.iter("Private"): if private.attrib.get('entityRef', None) == actor.rolename: for private_action in private.iter("PrivateAction"): for controller_action in private_action.iter('ControllerAction'): module, args = OpenScenarioParser.get_controller( controller_action, self.config.catalogs) controller_atomic = ChangeActorControl( carla_actor, control_py_module=module, args=args) if controller_atomic is None: controller_atomic = ChangeActorControl(carla_actor, control_py_module=None, args={}) actor_init_behavior.add_child(controller_atomic) if actor.speed > 0: actor_init_behavior.add_child(ChangeActorTargetSpeed(carla_actor, actor.speed, init_speed=True)) init_behavior.add_child(actor_init_behavior) break return init_behavior def _create_behavior(self): """ Basic behavior do nothing, i.e. Idle """ story_behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="Story") joint_actor_list = self.other_actors + self.ego_vehicles + [None] for act in self.config.story.iter("Act"): act_sequence = py_trees.composites.Sequence( name="Act StartConditions and behaviours") start_conditions = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="StartConditions Group") parallel_behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="Maneuver + EndConditions Group") parallel_sequences = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="Maneuvers") for sequence in act.iter("ManeuverGroup"): sequence_behavior = py_trees.composites.Sequence(name=sequence.attrib.get('name')) repetitions = sequence.attrib.get('maximumExecutionCount', 1) for _ in range(int(repetitions)): actor_ids = [] for actor in sequence.iter("Actors"): for entity in actor.iter("EntityRef"): entity_name = entity.attrib.get('entityRef', None) for k, _ in enumerate(joint_actor_list): if joint_actor_list[k] and entity_name == joint_actor_list[k].attributes['role_name']: actor_ids.append(k) break if not actor_ids: print("Warning: Maneuvergroup {} does not use reference actors!".format( sequence.attrib.get('name'))) actor_ids.append(len(joint_actor_list) - 1) # Collect catalog reference maneuvers in order to process them at the same time as normal maneuvers catalog_maneuver_list = [] for catalog_reference in sequence.iter("CatalogReference"): catalog_maneuver = OpenScenarioParser.get_catalog_entry(self.config.catalogs, catalog_reference) catalog_maneuver_list.append(catalog_maneuver) all_maneuvers = itertools.chain(iter(catalog_maneuver_list), sequence.iter("Maneuver")) single_sequence_iteration = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=sequence_behavior.name) for maneuver in all_maneuvers: # Iterates through both CatalogReferences and Maneuvers maneuver_parallel = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="Maneuver " + maneuver.attrib.get('name')) for event in maneuver.iter("Event"): event_sequence = py_trees.composites.Sequence( name="Event " + event.attrib.get('name')) parallel_actions = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="Actions") for child in event.iter(): if child.tag == "Action": for actor_id in actor_ids: maneuver_behavior = OpenScenarioParser.convert_maneuver_to_atomic( child, joint_actor_list[actor_id], self.config.catalogs) maneuver_behavior = StoryElementStatusToBlackboard( maneuver_behavior, "ACTION", child.attrib.get('name')) parallel_actions.add_child( oneshot_behavior(variable_name=# See note in get_xml_path get_xml_path(self.config.story, sequence) + '>' + \ get_xml_path(maneuver, child), behaviour=maneuver_behavior)) if child.tag == "StartTrigger": # There is always one StartConditions block per Event parallel_condition_groups = self._create_condition_container( child, "Parallel Condition Groups", sequence, maneuver) event_sequence.add_child( parallel_condition_groups) parallel_actions = StoryElementStatusToBlackboard( parallel_actions, "EVENT", event.attrib.get('name')) event_sequence.add_child(parallel_actions) maneuver_parallel.add_child( oneshot_behavior(variable_name=get_xml_path(self.config.story, sequence) + '>' + get_xml_path(maneuver, event), # See get_xml_path behaviour=event_sequence)) maneuver_parallel = StoryElementStatusToBlackboard( maneuver_parallel, "MANEUVER", maneuver.attrib.get('name')) single_sequence_iteration.add_child( oneshot_behavior(variable_name=get_xml_path(self.config.story, sequence) + '>' + maneuver.attrib.get('name'), # See get_xml_path behaviour=maneuver_parallel)) # OpenSCENARIO refers to Sequences as Scenes in this instance single_sequence_iteration = StoryElementStatusToBlackboard( single_sequence_iteration, "SCENE", sequence.attrib.get('name')) single_sequence_iteration = repeatable_behavior( single_sequence_iteration, get_xml_path(self.config.story, sequence)) sequence_behavior.add_child(single_sequence_iteration) if sequence_behavior.children: parallel_sequences.add_child( oneshot_behavior(variable_name=get_xml_path(self.config.story, sequence), behaviour=sequence_behavior)) if parallel_sequences.children: parallel_sequences = StoryElementStatusToBlackboard( parallel_sequences, "ACT", act.attrib.get('name')) parallel_behavior.add_child(parallel_sequences) start_triggers = act.find("StartTrigger") if list(start_triggers) is not None: for start_condition in start_triggers: parallel_start_criteria = self._create_condition_container(start_condition, "StartConditions") if parallel_start_criteria.children: start_conditions.add_child(parallel_start_criteria) end_triggers = act.find("StopTrigger") if end_triggers is not None and list(end_triggers) is not None: for end_condition in end_triggers: parallel_end_criteria = self._create_condition_container( end_condition, "EndConditions", success_on_all=False) if parallel_end_criteria.children: parallel_behavior.add_child(parallel_end_criteria) if start_conditions.children: act_sequence.add_child(start_conditions) if parallel_behavior.children: act_sequence.add_child(parallel_behavior) if act_sequence.children: story_behavior.add_child(act_sequence) # Build behavior tree behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name="behavior") env_behavior = self._create_environment_behavior() if env_behavior is not None: behavior.add_child(oneshot_behavior(variable_name="InitialEnvironmentSettings", behaviour=env_behavior)) init_behavior = self._create_init_behavior() if init_behavior is not None: behavior.add_child(oneshot_behavior(variable_name="InitialActorSettings", behaviour=init_behavior)) behavior.add_child(story_behavior) return behavior def _create_condition_container(self, node, name='Conditions Group', sequence=None, maneuver=None, success_on_all=True): """ This is a generic function to handle conditions utilising ConditionGroups Each ConditionGroup is represented as a Sequence of Conditions The ConditionGroups are grouped under a SUCCESS_ON_ONE Parallel """ parallel_condition_groups = py_trees.composites.Parallel(name, policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) for condition_group in node.iter("ConditionGroup"): if success_on_all: condition_group_sequence = py_trees.composites.Parallel( name="Condition Group", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL) else: condition_group_sequence = py_trees.composites.Parallel( name="Condition Group", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) for condition in condition_group.iter("Condition"): criterion = OpenScenarioParser.convert_condition_to_atomic( condition, self.other_actors + self.ego_vehicles) if sequence is not None and maneuver is not None: xml_path = get_xml_path(self.config.story, sequence) + '>' + \ get_xml_path(maneuver, condition) # See note in get_xml_path else: xml_path = get_xml_path(self.config.story, condition) criterion = oneshot_behavior(variable_name=xml_path, behaviour=criterion) condition_group_sequence.add_child(criterion) if condition_group_sequence.children: parallel_condition_groups.add_child(condition_group_sequence) return parallel_condition_groups def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ parallel_criteria = py_trees.composites.Parallel("EndConditions (Criteria Group)", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) criteria = [] for endcondition in self.config.storyboard.iter("StopTrigger"): for condition in endcondition.iter("Condition"): if condition.attrib.get('name').startswith('criteria_'): condition.set('name', condition.attrib.get('name')[9:]) criteria.append(condition) for condition in criteria: criterion = OpenScenarioParser.convert_condition_to_atomic(condition, self.ego_vehicles) parallel_criteria.add_child(criterion) return parallel_criteria def __del__(self): """ Remove all actors upon deletion """ self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/opposite_vehicle_taking_priority.py ================================================ #!/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 . """ Scenarios in which another (opposite) vehicle 'illegally' takes priority, e.g. by running a red traffic light. """ from __future__ import print_function import sys import py_trees import carla from agents.navigation.local_planner import RoadOption from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, WaypointFollower, SyncArrival) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest, DrivenDistanceTest, MaxVelocityTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToLocation, InTriggerDistanceToNextIntersection, DriveDistance) from srunner.scenariomanager.timer import TimeOut from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import (get_crossing_point, get_geometric_linear_intersection, generate_target_waypoint_list) class OppositeVehicleRunningRedLight(BasicScenario): """ This class holds everything required for a scenario, in which an other vehicle takes priority from the ego vehicle, by running a red traffic light (while the ego vehicle has green) (Traffic Scenario 7) This is a single ego vehicle scenario """ # ego vehicle parameters _ego_max_velocity_allowed = 20 # Maximum allowed velocity [m/s] _ego_avg_velocity_expected = 4 # Average expected velocity [m/s] _ego_expected_driven_distance = 70 # Expected driven distance [m] _ego_distance_to_traffic_light = 32 # Trigger distance to traffic light [m] _ego_distance_to_drive = 40 # Allowed distance to drive # other vehicle _other_actor_target_velocity = 10 # Target velocity of other vehicle _other_actor_max_brake = 1.0 # Maximum brake of other vehicle _other_actor_distance = 50 # Distance the other vehicle should drive _traffic_light = None def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): """ Setup all relevant parameters and create scenario and instantiate scenario manager """ self._other_actor_transform = None # Timeout of scenario in seconds self.timeout = timeout super(OppositeVehicleRunningRedLight, self).__init__("OppositeVehicleRunningRedLight", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) self._traffic_light = CarlaDataProvider.get_next_traffic_light(self.ego_vehicles[0], False) if self._traffic_light is None: print("No traffic light for the given location of the ego vehicle found") sys.exit(-1) self._traffic_light.set_state(carla.TrafficLightState.Green) self._traffic_light.set_green_time(self.timeout) # other vehicle's traffic light traffic_light_other = CarlaDataProvider.get_next_traffic_light(self.other_actors[0], False) if traffic_light_other is None: print("No traffic light for the given location of the other vehicle found") sys.exit(-1) traffic_light_other.set_state(carla.TrafficLightState.Red) traffic_light_other.set_red_time(self.timeout) def _initialize_actors(self, config): """ Custom initialization """ self._other_actor_transform = config.other_actors[0].transform first_vehicle_transform = carla.Transform( carla.Location(config.other_actors[0].transform.location.x, config.other_actors[0].transform.location.y, config.other_actors[0].transform.location.z), config.other_actors[0].transform.rotation) first_vehicle = CarlaDataProvider.request_new_actor(config.other_actors[0].model, first_vehicle_transform) self.other_actors.append(first_vehicle) def _create_behavior(self): """ Scenario behavior: The other vehicle waits until the ego vehicle is close enough to the intersection and that its own traffic light is red. Then, it will start driving and 'illegally' cross the intersection. After a short distance it should stop again, outside of the intersection. The ego vehicle has to avoid the crash, but continue driving after the intersection is clear. If this does not happen within 120 seconds, a timeout stops the scenario """ crossing_point_dynamic = get_crossing_point(self.ego_vehicles[0]) # start condition startcondition = InTriggerDistanceToLocation( self.ego_vehicles[0], crossing_point_dynamic, self._ego_distance_to_traffic_light, name="Waiting for start position") sync_arrival_parallel = py_trees.composites.Parallel( "Synchronize arrival times", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) location_of_collision_dynamic = get_geometric_linear_intersection(self.ego_vehicles[0], self.other_actors[0]) sync_arrival = SyncArrival( self.other_actors[0], self.ego_vehicles[0], location_of_collision_dynamic) sync_arrival_stop = InTriggerDistanceToNextIntersection(self.other_actors[0], 5) sync_arrival_parallel.add_child(sync_arrival) sync_arrival_parallel.add_child(sync_arrival_stop) # Generate plan for WaypointFollower turn = 0 # drive straight ahead plan = [] # generating waypoints until intersection (target_waypoint) plan, target_waypoint = generate_target_waypoint_list( CarlaDataProvider.get_map().get_waypoint(self.other_actors[0].get_location()), turn) # Generating waypoint list till next intersection wp_choice = target_waypoint.next(5.0) while len(wp_choice) == 1: target_waypoint = wp_choice[0] plan.append((target_waypoint, RoadOption.LANEFOLLOW)) wp_choice = target_waypoint.next(5.0) continue_driving = py_trees.composites.Parallel( "ContinueDriving", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) continue_driving_waypoints = WaypointFollower( self.other_actors[0], self._other_actor_target_velocity, plan=plan, avoid_collision=False) continue_driving_distance = DriveDistance( self.other_actors[0], self._other_actor_distance, name="Distance") continue_driving_timeout = TimeOut(10) continue_driving.add_child(continue_driving_waypoints) continue_driving.add_child(continue_driving_distance) continue_driving.add_child(continue_driving_timeout) # finally wait that ego vehicle drove a specific distance wait = DriveDistance( self.ego_vehicles[0], self._ego_distance_to_drive, name="DriveDistance") # Build behavior tree sequence = py_trees.composites.Sequence("Sequence Behavior") sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform)) sequence.add_child(startcondition) sequence.add_child(sync_arrival_parallel) sequence.add_child(continue_driving) sequence.add_child(wait) sequence.add_child(ActorDestroy(self.other_actors[0])) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] max_velocity_criterion = MaxVelocityTest( self.ego_vehicles[0], self._ego_max_velocity_allowed, optional=True) collision_criterion = CollisionTest(self.ego_vehicles[0]) driven_distance_criterion = DrivenDistanceTest( self.ego_vehicles[0], self._ego_expected_driven_distance) criteria.append(max_velocity_criterion) criteria.append(collision_criterion) criteria.append(driven_distance_criterion) # Add the collision and lane checks for all vehicles as well for vehicle in self.other_actors: collision_criterion = CollisionTest(vehicle) criteria.append(collision_criterion) return criteria def __del__(self): """ Remove all actors and traffic lights upon deletion """ self._traffic_light = None self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/other_leading_vehicle.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Other Leading Vehicle scenario: The scenario realizes a common driving behavior, in which the user-controlled ego vehicle follows a leading car driving down a given road. At some point the leading car has to decelerate. The ego vehicle has to react accordingly by changing lane to avoid a collision and follow the leading car in other lane. The scenario ends either via a timeout, or if the ego vehicle drives some distance. """ import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, WaypointFollower, ActorDestroy) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle, DriveDistance) from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import get_waypoint_in_distance class OtherLeadingVehicle(BasicScenario): """ This class holds everything required for a simple "Other Leading Vehicle" scenario involving a user controlled vehicle and two other actors. Traffic Scenario 05 This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=80): """ Setup all relevant parameters and create scenario """ self._world = world self._map = CarlaDataProvider.get_map() self._first_vehicle_location = 35 self._second_vehicle_location = self._first_vehicle_location + 1 self._ego_vehicle_drive_distance = self._first_vehicle_location * 4 self._first_vehicle_speed = 55 self._second_vehicle_speed = 45 self._reference_waypoint = self._map.get_waypoint(config.trigger_points[0].location) self._other_actor_max_brake = 1.0 self._first_actor_transform = None self._second_actor_transform = None # Timeout of scenario in seconds self.timeout = timeout super(OtherLeadingVehicle, self).__init__("VehicleDeceleratingInMultiLaneSetUp", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) def _initialize_actors(self, config): """ Custom initialization """ first_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._first_vehicle_location) second_vehicle_waypoint, _ = get_waypoint_in_distance(self._reference_waypoint, self._second_vehicle_location) second_vehicle_waypoint = second_vehicle_waypoint.get_left_lane() first_vehicle_transform = carla.Transform(first_vehicle_waypoint.transform.location, first_vehicle_waypoint.transform.rotation) second_vehicle_transform = carla.Transform(second_vehicle_waypoint.transform.location, second_vehicle_waypoint.transform.rotation) first_vehicle = CarlaDataProvider.request_new_actor('vehicle.nissan.patrol', first_vehicle_transform) second_vehicle = CarlaDataProvider.request_new_actor('vehicle.audi.tt', second_vehicle_transform) self.other_actors.append(first_vehicle) self.other_actors.append(second_vehicle) self._first_actor_transform = first_vehicle_transform self._second_actor_transform = second_vehicle_transform def _create_behavior(self): """ The scenario defined after is a "other leading vehicle" scenario. After invoking this scenario, the user controlled vehicle has to drive towards the moving other actors, then make the leading actor to decelerate when user controlled vehicle is at some close distance. Finally, the user-controlled vehicle has to change lane to avoid collision and follow other leading actor in other lane to end the scenario. If this does not happen within 90 seconds, a timeout stops the scenario or the ego vehicle drives certain distance and stops the scenario. """ # start condition driving_in_same_direction = py_trees.composites.Parallel("All actors driving in same direction", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) leading_actor_sequence_behavior = py_trees.composites.Sequence("Decelerating actor sequence behavior") # both actors moving in same direction keep_velocity = py_trees.composites.Parallel("Trigger condition for deceleration", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) keep_velocity.add_child(WaypointFollower(self.other_actors[0], self._first_vehicle_speed, avoid_collision=True)) keep_velocity.add_child(InTriggerDistanceToVehicle(self.other_actors[0], self.ego_vehicles[0], 55)) # Decelerating actor sequence behavior decelerate = self._first_vehicle_speed / 3.2 leading_actor_sequence_behavior.add_child(keep_velocity) leading_actor_sequence_behavior.add_child(WaypointFollower(self.other_actors[0], decelerate, avoid_collision=True)) # end condition ego_drive_distance = DriveDistance(self.ego_vehicles[0], self._ego_vehicle_drive_distance) # Build behavior tree sequence = py_trees.composites.Sequence("Scenario behavior") parallel_root = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) parallel_root.add_child(ego_drive_distance) parallel_root.add_child(driving_in_same_direction) driving_in_same_direction.add_child(leading_actor_sequence_behavior) driving_in_same_direction.add_child(WaypointFollower(self.other_actors[1], self._second_vehicle_speed, avoid_collision=True)) sequence.add_child(ActorTransformSetter(self.other_actors[0], self._first_actor_transform)) sequence.add_child(ActorTransformSetter(self.other_actors[1], self._second_actor_transform)) sequence.add_child(parallel_root) sequence.add_child(ActorDestroy(self.other_actors[0])) sequence.add_child(ActorDestroy(self.other_actors[1])) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collision_criterion = CollisionTest(self.ego_vehicles[0]) criteria.append(collision_criterion) return criteria def __del__(self): self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/route_scenario.py ================================================ #!/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 numpy.random as random import py_trees import carla from agents.navigation.local_planner import RoadOption # 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 FollowLeadingVehicle 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 SignalJunctionCrossingRoute, NoSignalJunctionCrossingRoute from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, InRouteTest, RouteCompletionTest, OutsideRouteLanesTest, RunningRedLightTest, RunningStopTest, ActorSpeedAboveThresholdTest) SECONDS_GIVEN_PER_METERS = 0.4 import os NUMBER_CLASS_TRANSLATION = { "Scenario1": ControlLoss, "Scenario2": FollowLeadingVehicle, "Scenario3": DynamicObjectCrossing, "Scenario4": VehicleTurningRoute, "Scenario5": OtherLeadingVehicle, "Scenario6": ManeuverOppositeDirection, "Scenario7": SignalJunctionCrossingRoute, "Scenario8": SignalJunctionCrossingRoute, "Scenario9": SignalJunctionCrossingRoute, "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) ego_vehicle = self._update_ego_vehicle() self.list_scenarios = self._build_scenario_instances(world, ego_vehicle, self.sampled_scenarios_definitions, scenarios_per_tick=5, timeout=self.timeout, debug_mode=debug_mode) self.is_eval = (os.environ['IS_EVAL'] == "True") print("IS_EVAL", self.is_eval) super(RouteScenario, self).__init__(name=config.name, ego_vehicles=[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(world, 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)) 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=1.0, persistency=50000.0) 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) size = 0.2 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 size = 0.1 world.debug.draw_point(wp, size=size, 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 _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 = random.RandomState(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('vehicle.lincoln.mkz2017', 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': 120, 'Town02': 100, 'Town03': 120, 'Town04': 200, 'Town05': 120, 'Town06': 150, 'Town07': 110, 'Town08': 180, 'Town09': 300, 'Town10': 120, } amount = town_amount[config.town] if config.town in town_amount else 0 if os.environ["BENCHMARK"] == "town05long": amount = 120 print("----------------Eval with Town05 Long, amount=120", flush=True) if os.environ["BENCHMARK"] == "longest6": amount = 500 print("----------------Eval with Longest6, amount=500", flush=True) new_actors = CarlaDataProvider.request_new_batch_actors('vehicle.*', amount, carla.Transform(), autopilot=True, random_location=True, rolename='background') if new_actors is None: raise Exception("Error: Unable to add the background activity, all spawn points were occupied") 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() ================================================ FILE: scenario_runner/srunner/scenarios/signalized_junction_left_turn.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Collection of traffic scenarios where the ego vehicle (hero) is making a left turn """ from six.moves.queue import Queue # pylint: disable=relative-import import py_trees import carla from agents.navigation.local_planner import RoadOption from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, ActorSource, ActorSink, WaypointFollower) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import generate_target_waypoint class SignalizedJunctionLeftTurn(BasicScenario): """ Implementation class for Hero Vehicle turning left at signalized junction scenario, Traffic Scenario 08. This is a single ego vehicle scenario """ timeout = 80 # Timeout of scenario in seconds def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=80): """ Setup all relevant parameters and create scenario """ self._world = world self._map = CarlaDataProvider.get_map() self._target_vel = 6.9 self._brake_value = 0.5 self._ego_distance = 110 self._traffic_light = None self._other_actor_transform = None self._blackboard_queue_name = 'SignalizedJunctionLeftTurn/actor_flow_queue' self._queue = py_trees.blackboard.Blackboard().set(self._blackboard_queue_name, Queue()) self._initialized = True super(SignalizedJunctionLeftTurn, self).__init__("TurnLeftAtSignalizedJunction", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) self._traffic_light = CarlaDataProvider.get_next_traffic_light(self.ego_vehicles[0], False) traffic_light_other = CarlaDataProvider.get_next_traffic_light(self.other_actors[0], False) if self._traffic_light is None or traffic_light_other is None: raise RuntimeError("No traffic light for the given location found") self._traffic_light.set_state(carla.TrafficLightState.Green) self._traffic_light.set_green_time(self.timeout) # other vehicle's traffic light traffic_light_other.set_state(carla.TrafficLightState.Green) traffic_light_other.set_green_time(self.timeout) def _initialize_actors(self, config): """ Custom initialization """ self._other_actor_transform = config.other_actors[0].transform first_vehicle_transform = carla.Transform( carla.Location(config.other_actors[0].transform.location.x, config.other_actors[0].transform.location.y, config.other_actors[0].transform.location.z - 500), config.other_actors[0].transform.rotation) first_vehicle = CarlaDataProvider.request_new_actor(config.other_actors[0].model, self._other_actor_transform) first_vehicle.set_transform(first_vehicle_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ Hero vehicle is turning left in an urban area, at a signalized intersection, while other actor coming straight .The hero actor may turn left either before other actor passes intersection or later, without any collision. After 80 seconds, a timeout stops the scenario. """ sequence = py_trees.composites.Sequence("Sequence Behavior") # Selecting straight path at intersection target_waypoint = generate_target_waypoint( CarlaDataProvider.get_map().get_waypoint(self.other_actors[0].get_location()), 0) # Generating waypoint list till next intersection plan = [] wp_choice = target_waypoint.next(1.0) while not wp_choice[0].is_intersection: target_waypoint = wp_choice[0] plan.append((target_waypoint, RoadOption.LANEFOLLOW)) wp_choice = target_waypoint.next(1.0) # adding flow of actors actor_source = ActorSource( ['vehicle.tesla.model3', 'vehicle.audi.tt'], self._other_actor_transform, 15, self._blackboard_queue_name) # destroying flow of actors actor_sink = ActorSink(plan[-1][0].transform.location, 10) # follow waypoints untill next intersection move_actor = WaypointFollower(self.other_actors[0], self._target_vel, plan=plan, blackboard_queue_name=self._blackboard_queue_name, avoid_collision=True) # wait wait = DriveDistance(self.ego_vehicles[0], self._ego_distance) # Behavior tree root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) root.add_child(wait) root.add_child(actor_source) root.add_child(actor_sink) root.add_child(move_actor) sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform)) sequence.add_child(root) sequence.add_child(ActorDestroy(self.other_actors[0])) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collison_criteria = CollisionTest(self.ego_vehicles[0]) criteria.append(collison_criteria) return criteria def __del__(self): self._traffic_light = None self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/scenarios/signalized_junction_right_turn.py ================================================ #!/usr/bin/env python # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Collection of traffic scenarios where the ego vehicle (hero) is making a right turn """ from __future__ import print_function import sys import py_trees import carla from agents.navigation.local_planner import RoadOption from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (ActorTransformSetter, ActorDestroy, StopVehicle, SyncArrival, WaypointFollower) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import DriveDistance, InTriggerDistanceToLocation from srunner.scenarios.basic_scenario import BasicScenario from srunner.tools.scenario_helper import (get_geometric_linear_intersection, get_crossing_point, generate_target_waypoint) class SignalizedJunctionRightTurn(BasicScenario): """ Implementation class for Hero Vehicle turning right at signalized junction scenario, Traffic Scenario 09. This is a single ego vehicle scenario """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=80): """ Setup all relevant parameters and create scenario """ self._target_vel = 6.9 self._brake_value = 0.5 self._ego_distance = 40 self._traffic_light = None self._other_actor_transform = None # Timeout of scenario in seconds self.timeout = timeout super(SignalizedJunctionRightTurn, self).__init__("HeroActorTurningRightAtSignalizedJunction", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) self._traffic_light = CarlaDataProvider.get_next_traffic_light(self.ego_vehicles[0], False) if self._traffic_light is None: print("No traffic light for the given location of the ego vehicle found") sys.exit(-1) self._traffic_light.set_state(carla.TrafficLightState.Red) self._traffic_light.set_red_time(self.timeout) # other vehicle's traffic light traffic_light_other = CarlaDataProvider.get_next_traffic_light(self.other_actors[0], False) if traffic_light_other is None: print("No traffic light for the given location of the other vehicle found") sys.exit(-1) traffic_light_other.set_state(carla.TrafficLightState.Green) traffic_light_other.set_green_time(self.timeout) def _initialize_actors(self, config): """ Custom initialization """ self._other_actor_transform = config.other_actors[0].transform first_vehicle_transform = carla.Transform( carla.Location(config.other_actors[0].transform.location.x, config.other_actors[0].transform.location.y, config.other_actors[0].transform.location.z - 500), config.other_actors[0].transform.rotation) first_vehicle = CarlaDataProvider.request_new_actor(config.other_actors[0].model, first_vehicle_transform) first_vehicle.set_simulate_physics(enabled=False) self.other_actors.append(first_vehicle) def _create_behavior(self): """ Hero vehicle is turning right in an urban area, at a signalized intersection, while other actor coming straight from left.The hero actor may turn right either before other actor passes intersection or later, without any collision. After 80 seconds, a timeout stops the scenario. """ location_of_collision_dynamic = get_geometric_linear_intersection(self.ego_vehicles[0], self.other_actors[0]) crossing_point_dynamic = get_crossing_point(self.other_actors[0]) sync_arrival = SyncArrival( self.other_actors[0], self.ego_vehicles[0], location_of_collision_dynamic) sync_arrival_stop = InTriggerDistanceToLocation(self.other_actors[0], crossing_point_dynamic, 5) sync_arrival_parallel = py_trees.composites.Parallel( "Synchronize arrival times", policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) sync_arrival_parallel.add_child(sync_arrival) sync_arrival_parallel.add_child(sync_arrival_stop) # Selecting straight path at intersection target_waypoint = generate_target_waypoint( CarlaDataProvider.get_map().get_waypoint(self.other_actors[0].get_location()), 0) # Generating waypoint list till next intersection plan = [] wp_choice = target_waypoint.next(1.0) while not wp_choice[0].is_intersection: target_waypoint = wp_choice[0] plan.append((target_waypoint, RoadOption.LANEFOLLOW)) wp_choice = target_waypoint.next(1.0) move_actor = WaypointFollower(self.other_actors[0], self._target_vel, plan=plan) waypoint_follower_end = InTriggerDistanceToLocation( self.other_actors[0], plan[-1][0].transform.location, 10) move_actor_parallel = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) move_actor_parallel.add_child(move_actor) move_actor_parallel.add_child(waypoint_follower_end) # stop other actor stop = StopVehicle(self.other_actors[0], self._brake_value) # end condition end_condition = DriveDistance(self.ego_vehicles[0], self._ego_distance) # Behavior tree sequence = py_trees.composites.Sequence() sequence.add_child(ActorTransformSetter(self.other_actors[0], self._other_actor_transform)) sequence.add_child(sync_arrival_parallel) sequence.add_child(move_actor_parallel) sequence.add_child(stop) sequence.add_child(end_condition) sequence.add_child(ActorDestroy(self.other_actors[0])) return sequence def _create_test_criteria(self): """ A list of all test criteria will be created that is later used in parallel behavior tree. """ criteria = [] collison_criteria = CollisionTest(self.ego_vehicles[0]) criteria.append(collison_criteria) return criteria def __del__(self): self._traffic_light = None self.remove_all_actors() ================================================ FILE: scenario_runner/srunner/tools/__init__.py ================================================ ================================================ FILE: scenario_runner/srunner/tools/openscenario_parser.py ================================================ #!/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 a parser for scenario configuration files based on OpenSCENARIO """ from distutils.util import strtobool import copy import datetime import math import operator import py_trees import carla from srunner.scenariomanager.carla_data_provider import CarlaDataProvider from srunner.scenariomanager.weather_sim import Weather from srunner.scenariomanager.scenarioatomics.atomic_behaviors import (TrafficLightStateSetter, ActorTransformSetterToOSCPosition, RunScript, ChangeWeather, ChangeAutoPilot, ChangeRoadFriction, ChangeActorTargetSpeed, ChangeActorControl, ChangeActorWaypoints, ChangeActorWaypointsToReachPosition, ChangeActorLateralMotion, Idle) # pylint: disable=unused-import # For the following includes the pylint check is disabled, as these are accessed via globals() from srunner.scenariomanager.scenarioatomics.atomic_criteria import (CollisionTest, MaxVelocityTest, DrivenDistanceTest, AverageVelocityTest, KeepLaneTest, ReachedRegionTest, OnSidewalkTest, WrongLaneTest, InRadiusRegionTest, InRouteTest, RouteCompletionTest, RunningRedLightTest, RunningStopTest, OffRoadTest, EndofRoadTest) # pylint: enable=unused-import from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import (InTriggerDistanceToVehicle, InTriggerDistanceToOSCPosition, InTimeToArrivalToOSCPosition, InTimeToArrivalToVehicle, DriveDistance, StandStill, OSCStartEndCondition, TriggerAcceleration, RelativeVelocityToOtherActor, TimeOfDayComparison, TriggerVelocity, WaitForTrafficLightState) from srunner.scenariomanager.timer import TimeOut, SimulationTimeCondition from srunner.tools.py_trees_port import oneshot_behavior class OpenScenarioParser(object): """ Pure static class providing conversions from OpenSCENARIO elements to ScenarioRunner elements """ operators = { "greaterThan": operator.gt, "lessThan": operator.lt, "equalTo": operator.eq } actor_types = { "pedestrian": "walker", "vehicle": "vehicle", "miscellaneous": "miscellaneous" } tl_states = { "GREEN": carla.TrafficLightState.Green, "YELLOW": carla.TrafficLightState.Yellow, "RED": carla.TrafficLightState.Red, "OFF": carla.TrafficLightState.Off, } global_osc_parameters = dict() use_carla_coordinate_system = False osc_filepath = None @staticmethod def get_traffic_light_from_osc_name(name): """ Returns a carla.TrafficLight instance that matches the name given """ traffic_light = None # Given by id if name.startswith("id="): tl_id = name[3:] for carla_tl in CarlaDataProvider.get_world().get_actors().filter('traffic.traffic_light'): if carla_tl.id == tl_id: traffic_light = carla_tl break # Given by position elif name.startswith("pos="): tl_pos = name[4:] pos = tl_pos.split(",") for carla_tl in CarlaDataProvider.get_world().get_actors().filter('traffic.traffic_light'): carla_tl_location = carla_tl.get_transform().location distance = carla_tl_location.distance(carla.Location(float(pos[0]), float(pos[1]), carla_tl_location.z)) if distance < 2.0: traffic_light = carla_tl break if traffic_light is None: raise AttributeError("Unknown traffic light {}".format(name)) return traffic_light @staticmethod def set_osc_filepath(filepath): """ Set path of OSC file. This is required if for example custom commands are provided with relative paths. """ OpenScenarioParser.osc_filepath = filepath @staticmethod def set_use_carla_coordinate_system(): """ CARLA internally uses a left-hand coordinate system (Unreal), but OpenSCENARIO and OpenDRIVE are intended for right-hand coordinate system. Hence, we need to invert the coordinates, if the scenario does not use CARLA coordinates, but instead right-hand coordinates. """ OpenScenarioParser.use_carla_coordinate_system = True @staticmethod def set_parameters(xml_tree, additional_parameter_dict=None): """ Parse the xml_tree, and replace all parameter references with the actual values. Note: Parameter names must not start with "$", however when referencing a parameter the reference has to start with "$". https://releases.asam.net/OpenSCENARIO/1.0.0/ASAM_OpenSCENARIO_BS-1-2_User-Guide_V1-0-0.html#_re_use_mechanisms Args: xml_tree: Containing all nodes that should be updated additional_parameter_dict (dictionary): Additional parameters as dict (key, value). Optional. returns: updated xml_tree, dictonary containing all parameters and their values """ parameter_dict = dict() if additional_parameter_dict is not None: parameter_dict = additional_parameter_dict parameters = xml_tree.find('ParameterDeclarations') if parameters is None and not parameter_dict: return xml_tree, parameter_dict if parameters is None: parameters = [] for parameter in parameters: name = parameter.attrib.get('name') value = parameter.attrib.get('value') parameter_dict[name] = value for node in xml_tree.iter(): for key in node.attrib: for param in sorted(parameter_dict, key=len, reverse=True): if "$" + param in node.attrib[key]: node.attrib[key] = node.attrib[key].replace("$" + param, parameter_dict[param]) return xml_tree, parameter_dict @staticmethod def set_global_parameters(parameter_dict): """ Set global_osc_parameter dictionary Args: parameter_dict (Dictionary): Input for global_osc_parameter """ OpenScenarioParser.global_osc_parameters = parameter_dict @staticmethod def get_catalog_entry(catalogs, catalog_reference): """ Get catalog entry referenced by catalog_reference included correct parameter settings Args: catalogs (Dictionary of dictionaries): List of all catalogs and their entries catalog_reference (XML ElementTree): Reference containing the exact catalog to be used returns: Catalog entry (XML ElementTree) """ entry = catalogs[catalog_reference.attrib.get("catalogName")][catalog_reference.attrib.get("entryName")] entry_copy = copy.deepcopy(entry) catalog_copy = copy.deepcopy(catalog_reference) entry = OpenScenarioParser.assign_catalog_parameters(entry_copy, catalog_copy) return entry @staticmethod def assign_catalog_parameters(entry_instance, catalog_reference): """ Parse catalog_reference, and replace all parameter references in entry_instance by the values provided in catalog_reference. Not to be used from outside this class. Args: entry_instance (XML ElementTree): Entry to be updated catalog_reference (XML ElementTree): Reference containing the exact parameter values returns: updated entry_instance with updated parameter values """ parameter_dict = dict() for elem in entry_instance.iter(): if elem.find('ParameterDeclarations') is not None: parameters = elem.find('ParameterDeclarations') for parameter in parameters: name = parameter.attrib.get('name') value = parameter.attrib.get('value') parameter_dict[name] = value for parameter_assignments in catalog_reference.iter("ParameterAssignments"): for parameter_assignment in parameter_assignments.iter("ParameterAssignment"): parameter = parameter_assignment.attrib.get("parameterRef") value = parameter_assignment.attrib.get("value") parameter_dict[parameter] = value for node in entry_instance.iter(): for key in node.attrib: for param in sorted(parameter_dict, key=len, reverse=True): if "$" + param in node.attrib[key]: node.attrib[key] = node.attrib[key].replace("$" + param, parameter_dict[param]) OpenScenarioParser.set_parameters(entry_instance, OpenScenarioParser.global_osc_parameters) return entry_instance @staticmethod def get_friction_from_env_action(xml_tree, catalogs): """ Extract the CARLA road friction coefficient from an OSC EnvironmentAction Args: xml_tree: Containing the EnvironmentAction, or the reference to the catalog it is defined in. catalogs: XML Catalogs that could contain the EnvironmentAction returns: friction (float) """ set_environment = next(xml_tree.iter("EnvironmentAction")) if sum(1 for _ in set_environment.iter("Weather")) != 0: environment = set_environment.find("Environment") elif set_environment.find("CatalogReference") is not None: catalog_reference = set_environment.find("CatalogReference") environment = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference) friction = 1.0 road_condition = environment.iter("RoadCondition") for condition in road_condition: friction = condition.attrib.get('frictionScaleFactor') return friction @staticmethod def get_weather_from_env_action(xml_tree, catalogs): """ Extract the CARLA weather parameters from an OSC EnvironmentAction Args: xml_tree: Containing the EnvironmentAction, or the reference to the catalog it is defined in. catalogs: XML Catalogs that could contain the EnvironmentAction returns: Weather (srunner.scenariomanager.weather_sim.Weather) """ set_environment = next(xml_tree.iter("EnvironmentAction")) if sum(1 for _ in set_environment.iter("Weather")) != 0: environment = set_environment.find("Environment") elif set_environment.find("CatalogReference") is not None: catalog_reference = set_environment.find("CatalogReference") environment = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference) weather = environment.find("Weather") sun = weather.find("Sun") carla_weather = carla.WeatherParameters() carla_weather.sun_azimuth_angle = math.degrees(float(sun.attrib.get('azimuth', 0))) carla_weather.sun_altitude_angle = math.degrees(float(sun.attrib.get('elevation', 0))) carla_weather.cloudiness = 100 - float(sun.attrib.get('intensity', 0)) * 100 fog = weather.find("Fog") carla_weather.fog_distance = float(fog.attrib.get('visualRange', 'inf')) if carla_weather.fog_distance < 1000: carla_weather.fog_density = 100 carla_weather.precipitation = 0 carla_weather.precipitation_deposits = 0 carla_weather.wetness = 0 carla_weather.wind_intensity = 0 precepitation = weather.find("Precipitation") if precepitation.attrib.get('precipitationType') == "rain": carla_weather.precipitation = float(precepitation.attrib.get('intensity')) * 100 carla_weather.precipitation_deposits = 100 # if it rains, make the road wet carla_weather.wetness = carla_weather.precipitation elif precepitation.attrib.get('type') == "snow": raise AttributeError("CARLA does not support snow precipitation") time_of_day = environment.find("TimeOfDay") weather_animation = strtobool(time_of_day.attrib.get("animation")) time = time_of_day.attrib.get("dateTime") dtime = datetime.datetime.strptime(time, "%Y-%m-%dT%H:%M:%S") return Weather(carla_weather, dtime, weather_animation) @staticmethod def get_controller(xml_tree, catalogs): """ Extract the object controller from the OSC XML or a catalog Args: xml_tree: Containing the controller information, or the reference to the catalog it is defined in. catalogs: XML Catalogs that could contain the EnvironmentAction returns: module: Python module containing the controller implementation args: Dictonary with (key, value) parameters for the controller """ assign_action = next(xml_tree.iter("AssignControllerAction")) properties = None if assign_action.find('Controller') is not None: properties = assign_action.find('Controller').find('Properties') elif assign_action.find("CatalogReference") is not None: catalog_reference = assign_action.find("CatalogReference") properties = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference).find('Properties') module = None args = {} for prop in properties: if prop.attrib.get('name') == "module": module = prop.attrib.get('value') else: args[prop.attrib.get('name')] = prop.attrib.get('value') override_action = xml_tree.find('OverrideControllerValueAction') for child in override_action: if strtobool(child.attrib.get('active')): raise NotImplementedError("Controller override actions are not yet supported") return module, args @staticmethod def get_route(xml_tree, catalogs): """ Extract the route from the OSC XML or a catalog Args: xml_tree: Containing the route information, or the reference to the catalog it is defined in. catalogs: XML Catalogs that could contain the Route returns: waypoints: List of route waypoints """ route = None if xml_tree.find('Route') is not None: route = xml_tree.find('Route') elif xml_tree.find('CatalogReference') is not None: catalog_reference = xml_tree.find("CatalogReference") route = OpenScenarioParser.get_catalog_entry(catalogs, catalog_reference) else: raise AttributeError("Unknown private FollowRoute action") waypoints = [] if route is not None: for waypoint in route.iter('Waypoint'): position = waypoint.find('Position') transform = OpenScenarioParser.convert_position_to_transform(position) waypoints.append(transform) return waypoints @staticmethod def convert_position_to_transform(position, actor_list=None): """ Convert an OpenScenario position into a CARLA transform Not supported: Road, RelativeRoad, Lane, RelativeLane as the PythonAPI currently does not provide sufficient access to OpenDrive information Also not supported is Route. This can be added by checking additional route information """ if position.find('WorldPosition') is not None: world_pos = position.find('WorldPosition') x = float(world_pos.attrib.get('x', 0)) y = float(world_pos.attrib.get('y', 0)) z = float(world_pos.attrib.get('z', 0)) yaw = math.degrees(float(world_pos.attrib.get('h', 0))) pitch = math.degrees(float(world_pos.attrib.get('p', 0))) roll = math.degrees(float(world_pos.attrib.get('r', 0))) if not OpenScenarioParser.use_carla_coordinate_system: y = y * (-1.0) yaw = yaw * (-1.0) return carla.Transform(carla.Location(x=x, y=y, z=z), carla.Rotation(yaw=yaw, pitch=pitch, roll=roll)) elif ((position.find('RelativeWorldPosition') is not None) or (position.find('RelativeObjectPosition') is not None) or (position.find('RelativeLanePosition') is not None)): if position.find('RelativeWorldPosition') is not None: rel_pos = position.find('RelativeWorldPosition') if position.find('RelativeObjectPosition') is not None: rel_pos = position.find('RelativeObjectPosition') if position.find('RelativeLanePosition') is not None: rel_pos = position.find('RelativeLanePosition') # get relative object and relative position obj = rel_pos.attrib.get('entityRef') obj_actor = None actor_transform = None if actor_list is not None: for actor in actor_list: if actor.rolename == obj: obj_actor = actor actor_transform = actor.transform else: for actor in CarlaDataProvider.get_world().get_actors(): if 'role_name' in actor.attributes and actor.attributes['role_name'] == obj: obj_actor = actor actor_transform = obj_actor.get_transform() break if obj_actor is None: raise AttributeError("Object '{}' provided as position reference is not known".format(obj)) # calculate orientation h, p, r is_absolute = False dyaw = 0 dpitch = 0 droll = 0 if rel_pos.find('Orientation') is not None: orientation = rel_pos.find('Orientation') is_absolute = (orientation.attrib.get('type') == "absolute") dyaw = math.degrees(float(orientation.attrib.get('h', 0))) dpitch = math.degrees(float(orientation.attrib.get('p', 0))) droll = math.degrees(float(orientation.attrib.get('r', 0))) if not OpenScenarioParser.use_carla_coordinate_system: dyaw = dyaw * (-1.0) yaw = actor_transform.rotation.yaw pitch = actor_transform.rotation.pitch roll = actor_transform.rotation.roll if not is_absolute: yaw = yaw + dyaw pitch = pitch + dpitch roll = roll + droll else: yaw = dyaw pitch = dpitch roll = droll # calculate location x, y, z # dx, dy, dz if ((position.find('RelativeWorldPosition') is not None) or (position.find('RelativeObjectPosition') is not None)): dx = float(rel_pos.attrib.get('dx', 0)) dy = float(rel_pos.attrib.get('dy', 0)) dz = float(rel_pos.attrib.get('dz', 0)) if not OpenScenarioParser.use_carla_coordinate_system: dy = dy * (-1.0) x = actor_transform.location.x + dx y = actor_transform.location.y + dy z = actor_transform.location.z + dz # dLane, ds, offset elif position.find('RelativeLanePosition') is not None: dlane = float(rel_pos.attrib.get('dLane')) ds = float(rel_pos.attrib.get('ds')) offset = float(rel_pos.attrib.get('offset', 0.0)) carla_map = CarlaDataProvider.get_map() relative_waypoint = carla_map.get_waypoint(actor_transform.location) if dlane == 0: wp = relative_waypoint elif dlane == -1: wp = relative_waypoint.get_left_lane() elif dlane == 1: wp = relative_waypoint.get_right_lane() if wp is None: raise AttributeError("Object '{}' position with dLane={} is not valid".format(obj, dlane)) if ds < 0: ds = (-1.0) * ds wp = wp.previous(ds)[-1] else: wp = wp.next(ds)[-1] # Adapt transform according to offset h = math.radians(wp.transform.rotation.yaw) x_offset = math.sin(h) * offset y_offset = math.cos(h) * offset if OpenScenarioParser.use_carla_coordinate_system: x_offset = x_offset * (-1.0) y_offset = y_offset * (-1.0) x = wp.transform.location.x + x_offset y = wp.transform.location.y + y_offset z = wp.transform.location.z return carla.Transform(carla.Location(x=x, y=y, z=z), carla.Rotation(yaw=yaw, pitch=pitch, roll=roll)) # Not implemented elif position.find('RoadPosition') is not None: raise NotImplementedError("Road positions are not yet supported") elif position.find('RelativeRoadPosition') is not None: raise NotImplementedError("RelativeRoad positions are not yet supported") elif position.find('LanePosition') is not None: lane_pos = position.find('LanePosition') road_id = int(lane_pos.attrib.get('roadId', 0)) lane_id = int(lane_pos.attrib.get('laneId', 0)) offset = float(lane_pos.attrib.get('offset', 0)) s = float(lane_pos.attrib.get('s', 0)) is_absolute = True waypoint = CarlaDataProvider.get_map().get_waypoint_xodr(road_id, lane_id, s) if waypoint is None: raise AttributeError("Lane position cannot be found") transform = waypoint.transform if lane_pos.find('Orientation') is not None: orientation = lane_pos.find('Orientation') dyaw = math.degrees(float(orientation.attrib.get('h', 0))) dpitch = math.degrees(float(orientation.attrib.get('p', 0))) droll = math.degrees(float(orientation.attrib.get('r', 0))) if not OpenScenarioParser.use_carla_coordinate_system: dyaw = dyaw * (-1.0) transform.rotation.yaw = transform.rotation.yaw + dyaw transform.rotation.pitch = transform.rotation.pitch + dpitch transform.rotation.roll = transform.rotation.roll + droll if offset != 0: forward_vector = transform.rotation.get_forward_vector() orthogonal_vector = carla.Vector3D(x=-forward_vector.y, y=forward_vector.x, z=forward_vector.z) transform.location.x = transform.location.x + offset * orthogonal_vector.x transform.location.y = transform.location.y + offset * orthogonal_vector.y return transform elif position.find('RoutePosition') is not None: raise NotImplementedError("Route positions are not yet supported") else: raise AttributeError("Unknown position") @staticmethod def convert_condition_to_atomic(condition, actor_list): """ Convert an OpenSCENARIO condition into a Behavior/Criterion atomic If there is a delay defined in the condition, then the condition is checked after the delay time passed by, e.g. . Note: Not all conditions are currently supported. """ atomic = None delay_atomic = None condition_name = condition.attrib.get('name') if condition.attrib.get('delay') is not None and str(condition.attrib.get('delay')) != '0': delay = float(condition.attrib.get('delay')) delay_atomic = TimeOut(delay) if condition.find('ByEntityCondition') is not None: trigger_actor = None # A-priori validation ensures that this will be not None triggered_actor = None for triggering_entities in condition.find('ByEntityCondition').iter('TriggeringEntities'): for entity in triggering_entities.iter('EntityRef'): for actor in actor_list: if entity.attrib.get('entityRef', None) == actor.attributes['role_name']: trigger_actor = actor break for entity_condition in condition.find('ByEntityCondition').iter('EntityCondition'): if entity_condition.find('EndOfRoadCondition') is not None: end_road_condition = entity_condition.find('EndOfRoadCondition') condition_duration = float(end_road_condition.attrib.get('duration')) atomic_cls = py_trees.meta.inverter(EndofRoadTest) atomic = atomic_cls( trigger_actor, condition_duration, terminate_on_failure=True, name=condition_name) elif entity_condition.find('CollisionCondition') is not None: collision_condition = entity_condition.find('CollisionCondition') if collision_condition.find('EntityRef') is not None: collision_entity = collision_condition.find('EntityRef') for actor in actor_list: if collision_entity.attrib.get('entityRef', None) == actor.attributes['role_name']: triggered_actor = actor break if triggered_actor is None: raise AttributeError("Cannot find actor '{}' for condition".format( collision_condition.attrib.get('entityRef', None))) atomic_cls = py_trees.meta.inverter(CollisionTest) atomic = atomic_cls(trigger_actor, other_actor=triggered_actor, terminate_on_failure=True, name=condition_name) elif collision_condition.find('ByType') is not None: collision_type = collision_condition.find('ByType').attrib.get('type', None) triggered_type = OpenScenarioParser.actor_types[collision_type] atomic_cls = py_trees.meta.inverter(CollisionTest) atomic = atomic_cls(trigger_actor, other_actor_type=triggered_type, terminate_on_failure=True, name=condition_name) else: atomic_cls = py_trees.meta.inverter(CollisionTest) atomic = atomic_cls(trigger_actor, terminate_on_failure=True, name=condition_name) elif entity_condition.find('OffroadCondition') is not None: off_condition = entity_condition.find('OffroadCondition') condition_duration = float(off_condition.attrib.get('duration')) atomic_cls = py_trees.meta.inverter(OffRoadTest) atomic = atomic_cls( trigger_actor, condition_duration, terminate_on_failure=True, name=condition_name) elif entity_condition.find('TimeHeadwayCondition') is not None: headtime_condition = entity_condition.find('TimeHeadwayCondition') condition_value = float(headtime_condition.attrib.get('value')) condition_rule = headtime_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] condition_freespace = strtobool(headtime_condition.attrib.get('freespace', False)) if condition_freespace: raise NotImplementedError( "TimeHeadwayCondition: freespace attribute is currently not implemented") condition_along_route = strtobool(headtime_condition.attrib.get('alongRoute', False)) for actor in actor_list: if headtime_condition.attrib.get('entityRef', None) == actor.attributes['role_name']: triggered_actor = actor break if triggered_actor is None: raise AttributeError("Cannot find actor '{}' for condition".format( headtime_condition.attrib.get('entityRef', None))) atomic = InTimeToArrivalToVehicle( trigger_actor, triggered_actor, condition_value, condition_along_route, condition_operator, condition_name ) elif entity_condition.find('TimeToCollisionCondition') is not None: ttc_condition = entity_condition.find('TimeToCollisionCondition') condition_rule = ttc_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] condition_value = ttc_condition.attrib.get('value') condition_target = ttc_condition.find('TimeToCollisionConditionTarget') condition_freespace = strtobool(ttc_condition.attrib.get('freespace', False)) if condition_freespace: raise NotImplementedError( "TimeToCollisionCondition: freespace attribute is currently not implemented") condition_along_route = strtobool(ttc_condition.attrib.get('alongRoute', False)) if condition_target.find('Position') is not None: position = condition_target.find('Position') atomic = InTimeToArrivalToOSCPosition( trigger_actor, position, condition_value, condition_along_route, condition_operator) else: for actor in actor_list: if ttc_condition.attrib.get('EntityRef', None) == actor.attributes['role_name']: triggered_actor = actor break if triggered_actor is None: raise AttributeError("Cannot find actor '{}' for condition".format( ttc_condition.attrib.get('EntityRef', None))) atomic = InTimeToArrivalToVehicle( trigger_actor, triggered_actor, condition_value, condition_along_route, condition_operator, condition_name) elif entity_condition.find('AccelerationCondition') is not None: accel_condition = entity_condition.find('AccelerationCondition') condition_value = float(accel_condition.attrib.get('value')) condition_rule = accel_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] atomic = TriggerAcceleration( trigger_actor, condition_value, condition_operator, condition_name) elif entity_condition.find('StandStillCondition') is not None: ss_condition = entity_condition.find('StandStillCondition') duration = float(ss_condition.attrib.get('duration')) atomic = StandStill(trigger_actor, condition_name, duration) elif entity_condition.find('SpeedCondition') is not None: spd_condition = entity_condition.find('SpeedCondition') condition_value = float(spd_condition.attrib.get('value')) condition_rule = spd_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] atomic = TriggerVelocity( trigger_actor, condition_value, condition_operator, condition_name) elif entity_condition.find('RelativeSpeedCondition') is not None: relspd_condition = entity_condition.find('RelativeSpeedCondition') condition_value = float(relspd_condition.attrib.get('value')) condition_rule = relspd_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] for actor in actor_list: if relspd_condition.attrib.get('entityRef', None) == actor.attributes['role_name']: triggered_actor = actor break if triggered_actor is None: raise AttributeError("Cannot find actor '{}' for condition".format( relspd_condition.attrib.get('entityRef', None))) atomic = RelativeVelocityToOtherActor( trigger_actor, triggered_actor, condition_value, condition_operator, condition_name) elif entity_condition.find('TraveledDistanceCondition') is not None: distance_condition = entity_condition.find('TraveledDistanceCondition') distance_value = float(distance_condition.attrib.get('value')) atomic = DriveDistance(trigger_actor, distance_value, name=condition_name) elif entity_condition.find('ReachPositionCondition') is not None: rp_condition = entity_condition.find('ReachPositionCondition') distance_value = float(rp_condition.attrib.get('tolerance')) position = rp_condition.find('Position') atomic = InTriggerDistanceToOSCPosition( trigger_actor, position, distance_value, name=condition_name) elif entity_condition.find('DistanceCondition') is not None: distance_condition = entity_condition.find('DistanceCondition') distance_value = float(distance_condition.attrib.get('value')) distance_rule = distance_condition.attrib.get('rule') distance_operator = OpenScenarioParser.operators[distance_rule] distance_freespace = strtobool(distance_condition.attrib.get('freespace', False)) if distance_freespace: raise NotImplementedError( "DistanceCondition: freespace attribute is currently not implemented") distance_along_route = strtobool(distance_condition.attrib.get('alongRoute', False)) if distance_condition.find('Position') is not None: position = distance_condition.find('Position') atomic = InTriggerDistanceToOSCPosition( trigger_actor, position, distance_value, distance_along_route, distance_operator, name=condition_name) elif entity_condition.find('RelativeDistanceCondition') is not None: distance_condition = entity_condition.find('RelativeDistanceCondition') distance_value = float(distance_condition.attrib.get('value')) distance_freespace = strtobool(distance_condition.attrib.get('freespace', False)) if distance_freespace: raise NotImplementedError( "RelativeDistanceCondition: freespace attribute is currently not implemented") if distance_condition.attrib.get('relativeDistanceType') == "cartesianDistance": for actor in actor_list: if distance_condition.attrib.get('entityRef', None) == actor.attributes['role_name']: triggered_actor = actor break if triggered_actor is None: raise AttributeError("Cannot find actor '{}' for condition".format( distance_condition.attrib.get('entityRef', None))) condition_rule = distance_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] atomic = InTriggerDistanceToVehicle( triggered_actor, trigger_actor, distance_value, condition_operator, name=condition_name) else: raise NotImplementedError( "RelativeDistance condition with the given specification is not yet supported") elif condition.find('ByValueCondition') is not None: value_condition = condition.find('ByValueCondition') if value_condition.find('ParameterCondition') is not None: parameter_condition = value_condition.find('ParameterCondition') arg_name = parameter_condition.attrib.get('parameterRef') value = parameter_condition.attrib.get('value') if value != '': arg_value = float(value) else: arg_value = 0 parameter_condition.attrib.get('rule') if condition_name in globals(): criterion_instance = globals()[condition_name] else: raise AttributeError( "The condition {} cannot be mapped to a criterion atomic".format(condition_name)) atomic = py_trees.composites.Parallel("Evaluation Criteria for multiple ego vehicles") for triggered_actor in actor_list: if arg_name != '': atomic.add_child(criterion_instance(triggered_actor, arg_value)) else: atomic.add_child(criterion_instance(triggered_actor)) elif value_condition.find('SimulationTimeCondition') is not None: simtime_condition = value_condition.find('SimulationTimeCondition') value = float(simtime_condition.attrib.get('value')) rule = simtime_condition.attrib.get('rule') atomic = SimulationTimeCondition(value, success_rule=rule) elif value_condition.find('TimeOfDayCondition') is not None: tod_condition = value_condition.find('TimeOfDayCondition') condition_date = tod_condition.attrib.get('dateTime') condition_rule = tod_condition.attrib.get('rule') condition_operator = OpenScenarioParser.operators[condition_rule] atomic = TimeOfDayComparison(condition_date, condition_operator, condition_name) elif value_condition.find('StoryboardElementStateCondition') is not None: state_condition = value_condition.find('StoryboardElementStateCondition') element_name = state_condition.attrib.get('storyboardElementRef') element_type = state_condition.attrib.get('storyboardElementType') state = state_condition.attrib.get('state') if state == "startTransition": atomic = OSCStartEndCondition(element_type, element_name, rule="START", name=state + "Condition") elif state == "stopTransition" or state == "endTransition" or state == "completeState": atomic = OSCStartEndCondition(element_type, element_name, rule="END", name=state + "Condition") else: raise NotImplementedError( "Only start, stop, endTransitions and completeState are currently supported") elif value_condition.find('UserDefinedValueCondition') is not None: raise NotImplementedError("ByValue UserDefinedValue conditions are not yet supported") elif value_condition.find('TrafficSignalCondition') is not None: tl_condition = value_condition.find('TrafficSignalCondition') name_condition = tl_condition.attrib.get('name') traffic_light = OpenScenarioParser.get_traffic_light_from_osc_name(name_condition) tl_state = tl_condition.attrib.get('state').upper() if tl_state not in OpenScenarioParser.tl_states: raise KeyError("CARLA only supports Green, Red, Yellow or Off") state_condition = OpenScenarioParser.tl_states[tl_state] atomic = WaitForTrafficLightState( traffic_light, state_condition, name=condition_name) elif value_condition.find('TrafficSignalControllerCondition') is not None: raise NotImplementedError("ByValue TrafficSignalController conditions are not yet supported") else: raise AttributeError("Unknown ByValue condition") else: raise AttributeError("Unknown condition") if delay_atomic is not None and atomic is not None: new_atomic = py_trees.composites.Sequence("delayed sequence") new_atomic.add_child(delay_atomic) new_atomic.add_child(atomic) else: new_atomic = atomic return new_atomic @staticmethod def convert_maneuver_to_atomic(action, actor, catalogs): """ Convert an OpenSCENARIO maneuver action into a Behavior atomic Note not all OpenSCENARIO actions are currently supported """ maneuver_name = action.attrib.get('name', 'unknown') if action.find('GlobalAction') is not None: global_action = action.find('GlobalAction') if global_action.find('InfrastructureAction') is not None: infrastructure_action = global_action.find('InfrastructureAction').find('TrafficSignalAction') if infrastructure_action.find('TrafficSignalStateAction') is not None: traffic_light_action = infrastructure_action.find('TrafficSignalStateAction') name_condition = traffic_light_action.attrib.get('name') traffic_light = OpenScenarioParser.get_traffic_light_from_osc_name(name_condition) tl_state = traffic_light_action.attrib.get('state').upper() if tl_state not in OpenScenarioParser.tl_states: raise KeyError("CARLA only supports Green, Red, Yellow or Off") traffic_light_state = OpenScenarioParser.tl_states[tl_state] atomic = TrafficLightStateSetter( traffic_light, traffic_light_state, name=maneuver_name + "_" + str(traffic_light.id)) else: raise NotImplementedError("TrafficLights can only be influenced via TrafficSignalStateAction") elif global_action.find('EnvironmentAction') is not None: weather_behavior = ChangeWeather( OpenScenarioParser.get_weather_from_env_action(global_action, catalogs)) friction_behavior = ChangeRoadFriction( OpenScenarioParser.get_friction_from_env_action(global_action, catalogs)) env_behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ALL, name=maneuver_name) env_behavior.add_child( oneshot_behavior(variable_name=maneuver_name + ">WeatherUpdate", behaviour=weather_behavior)) env_behavior.add_child( oneshot_behavior(variable_name=maneuver_name + ">FrictionUpdate", behaviour=friction_behavior)) return env_behavior else: raise NotImplementedError("Global actions are not yet supported") elif action.find('UserDefinedAction') is not None: user_defined_action = action.find('UserDefinedAction') if user_defined_action.find('CustomCommandAction') is not None: command = user_defined_action.find('CustomCommandAction').attrib.get('type') atomic = RunScript(command, base_path=OpenScenarioParser.osc_filepath, name=maneuver_name) elif action.find('PrivateAction') is not None: private_action = action.find('PrivateAction') if private_action.find('LongitudinalAction') is not None: private_action = private_action.find('LongitudinalAction') if private_action.find('SpeedAction') is not None: long_maneuver = private_action.find('SpeedAction') # duration and distance distance = float('inf') duration = float('inf') dimension = long_maneuver.find("SpeedActionDynamics").attrib.get('dynamicsDimension') if dimension == "distance": distance = float(long_maneuver.find("SpeedActionDynamics").attrib.get('value', float("inf"))) else: duration = float(long_maneuver.find("SpeedActionDynamics").attrib.get('value', float("inf"))) # absolute velocity with given target speed if long_maneuver.find("SpeedActionTarget").find("AbsoluteTargetSpeed") is not None: target_speed = float(long_maneuver.find("SpeedActionTarget").find( "AbsoluteTargetSpeed").attrib.get('value', 0)) atomic = ChangeActorTargetSpeed( actor, target_speed, distance=distance, duration=duration, name=maneuver_name) # relative velocity to given actor if long_maneuver.find("SpeedActionTarget").find("RelativeTargetSpeed") is not None: relative_speed = long_maneuver.find("SpeedActionTarget").find("RelativeTargetSpeed") obj = relative_speed.attrib.get('entityRef') value = float(relative_speed.attrib.get('value', 0)) value_type = relative_speed.attrib.get('speedTargetValueType') continuous = relative_speed.attrib.get('continuous') for traffic_actor in CarlaDataProvider.get_world().get_actors(): if 'role_name' in traffic_actor.attributes and traffic_actor.attributes['role_name'] == obj: obj_actor = traffic_actor atomic = ChangeActorTargetSpeed(actor, target_speed=0.0, relative_actor=obj_actor, value=value, value_type=value_type, continuous=continuous, distance=distance, duration=duration, name=maneuver_name) elif private_action.find('LongitudinalDistanceAction') is not None: raise NotImplementedError("Longitudinal distance actions are not yet supported") else: raise AttributeError("Unknown longitudinal action") elif private_action.find('LateralAction') is not None: private_action = private_action.find('LateralAction') if private_action.find('LaneChangeAction') is not None: # Note: LaneChangeActions are currently only supported for RelativeTargetLane # with +1 or -1 referring to the action actor lat_maneuver = private_action.find('LaneChangeAction') target_lane_rel = float(lat_maneuver.find("LaneChangeTarget").find( "RelativeTargetLane").attrib.get('value', 0)) # duration and distance distance = float('inf') duration = float('inf') dimension = lat_maneuver.find("LaneChangeActionDynamics").attrib.get('dynamicsDimension') if dimension == "distance": distance = float( lat_maneuver.find("LaneChangeActionDynamics").attrib.get('value', float("inf"))) else: duration = float( lat_maneuver.find("LaneChangeActionDynamics").attrib.get('value', float("inf"))) atomic = ChangeActorLateralMotion(actor, direction="left" if target_lane_rel < 0 else "right", distance_lane_change=distance, distance_other_lane=1000, name=maneuver_name) else: raise AttributeError("Unknown lateral action") elif private_action.find('VisibilityAction') is not None: raise NotImplementedError("Visibility actions are not yet supported") elif private_action.find('SynchronizeAction') is not None: raise NotImplementedError("Synchronization actions are not yet supported") elif private_action.find('ActivateControllerAction') is not None: private_action = private_action.find('ActivateControllerAction') activate = strtobool(private_action.attrib.get('longitudinal')) atomic = ChangeAutoPilot(actor, activate, name=maneuver_name) elif private_action.find('ControllerAction') is not None: controller_action = private_action.find('ControllerAction') module, args = OpenScenarioParser.get_controller(controller_action, catalogs) atomic = ChangeActorControl(actor, control_py_module=module, args=args) elif private_action.find('TeleportAction') is not None: position = private_action.find('TeleportAction') atomic = ActorTransformSetterToOSCPosition(actor, position, name=maneuver_name) elif private_action.find('RoutingAction') is not None: private_action = private_action.find('RoutingAction') if private_action.find('AssignRouteAction') is not None: # How to handle relative positions here? This might chance at runtime?! route_action = private_action.find('AssignRouteAction') waypoints = OpenScenarioParser.get_route(route_action, catalogs) atomic = ChangeActorWaypoints(actor, waypoints=waypoints, name=maneuver_name) elif private_action.find('FollowTrajectoryAction') is not None: raise NotImplementedError("Private FollowTrajectory actions are not yet supported") elif private_action.find('AcquirePositionAction') is not None: route_action = private_action.find('AcquirePositionAction') osc_position = route_action.find('Position') position = OpenScenarioParser.convert_position_to_transform(osc_position) atomic = ChangeActorWaypointsToReachPosition(actor, position=position, name=maneuver_name) else: raise AttributeError("Unknown private routing action") else: raise AttributeError("Unknown private action") else: if list(action): raise AttributeError("Unknown action: {}".format(maneuver_name)) else: return Idle(duration=0, name=maneuver_name) return atomic ================================================ FILE: scenario_runner/srunner/tools/py_trees_port.py ================================================ #!/usr/bin/env python # Copyright (c) 2015 Daniel Stonier # Copyright (c) 2020 Intel Corporation # # License: BSD # https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE """ This module provides a backport from newer py_trees releases (> 1.0) To use certain features also within ScenarioRunner, which uses py_trees version 0.8.x """ import py_trees class Decorator(py_trees.behaviour.Behaviour): """ A decorator is responsible for handling the lifecycle of a single child beneath This is taken from py_trees 1.2 to work with our current implementation that uses py_trees 0.8.2 """ def __init__(self, child, name): """ Common initialisation steps for a decorator - type checks and name construction (if None is given). Args: name (:obj:`str`): the decorator name child (:class:`~py_trees.behaviour.Behaviour`): the child to be decorated Raises: TypeError: if the child is not an instance of :class:`~py_trees.behaviour.Behaviour` """ # Checks if not isinstance(child, py_trees.behaviour.Behaviour): raise TypeError("A decorator's child must be an instance of py_trees.behaviours.Behaviour") # Initialise super(Decorator, self).__init__(name=name) self.children.append(child) # Give a convenient alias self.decorated = self.children[0] self.decorated.parent = self def tick(self): """ A decorator's tick is exactly the same as a normal proceedings for a Behaviour's tick except that it also ticks the decorated child node. Yields: :class:`~py_trees.behaviour.Behaviour`: a reference to itself or one of its children """ self.logger.debug("%s.tick()" % self.__class__.__name__) # initialise just like other behaviours/composites if self.status != py_trees.common.Status.RUNNING: self.initialise() # interrupt proceedings and process the child node # (including any children it may have as well) for node in self.decorated.tick(): yield node # resume normal proceedings for a Behaviour's tick new_status = self.update() if new_status not in list(py_trees.common.Status): self.logger.error( "A behaviour returned an invalid status, setting to INVALID [%s][%s]" % (new_status, self.name)) new_status = py_trees.common.Status.INVALID if new_status != py_trees.common.Status.RUNNING: self.stop(new_status) self.status = new_status yield self def stop(self, new_status=py_trees.common.Status.INVALID): """ As with other composites, it checks if the child is running and stops it if that is the case. Args: new_status (:class:`~py_trees.common.Status`): the behaviour is transitioning to this new status """ self.logger.debug("%s.stop(%s)" % (self.__class__.__name__, new_status)) self.terminate(new_status) # priority interrupt handling if new_status == py_trees.common.Status.INVALID: self.decorated.stop(new_status) # if the decorator returns SUCCESS/FAILURE and should stop the child if self.decorated.status == py_trees.common.Status.RUNNING: self.decorated.stop(py_trees.common.Status.INVALID) self.status = new_status def tip(self): """ Get the *tip* of this behaviour's subtree (if it has one) after it's last tick. This corresponds to the the deepest node that was running before the subtree traversal reversed direction and headed back to this node. """ if self.decorated.status != py_trees.common.Status.INVALID: return self.decorated.tip() return super(Decorator, self).tip() def oneshot_behavior(variable_name, behaviour, name=None): """ This is taken from py_trees.idiom.oneshot. """ if not name: name = behaviour.name subtree_root = py_trees.composites.Selector(name=name) # Initialize the variables blackboard = py_trees.blackboard.Blackboard() _ = blackboard.set(variable_name, False) # Wait until the scenario has ended check_flag = py_trees.blackboard.CheckBlackboardVariable( name=variable_name + " Done?", variable_name=variable_name, expected_value=True, clearing_policy=py_trees.common.ClearingPolicy.ON_INITIALISE ) set_flag = py_trees.blackboard.SetBlackboardVariable( name="Mark Done", variable_name=variable_name, variable_value=True ) # If it's a sequence, don't double-nest it in a redundant manner if isinstance(behaviour, py_trees.composites.Sequence): behaviour.add_child(set_flag) sequence = behaviour else: sequence = py_trees.composites.Sequence(name="OneShot") sequence.add_children([behaviour, set_flag]) subtree_root.add_children([check_flag, sequence]) return subtree_root ================================================ FILE: scenario_runner/srunner/tools/route_manipulation.py ================================================ #!/usr/bin/env python # Copyright (c) 2018-2019 Intel Labs. # authors: German Ros (german.ros@intel.com), Felipe Codevilla (felipe.alcm@gmail.com) # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Module to manipulate the routes, by making then more or less dense (Up to a certain parameter). It also contains functions to convert the CARLA world location do GPS coordinates. """ import math import xml.etree.ElementTree as ET from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO from agents.navigation.local_planner import RoadOption def _location_to_gps(lat_ref, lon_ref, location): """ Convert from world coordinates to GPS coordinates :param lat_ref: latitude reference for the current map :param lon_ref: longitude reference for the current map :param location: location to translate :return: dictionary with lat, lon and height """ EARTH_RADIUS_EQUA = 6378137.0 # pylint: disable=invalid-name scale = math.cos(lat_ref * math.pi / 180.0) mx = scale * lon_ref * math.pi * EARTH_RADIUS_EQUA / 180.0 my = scale * EARTH_RADIUS_EQUA * math.log(math.tan((90.0 + lat_ref) * math.pi / 360.0)) mx += location.x my -= location.y lon = mx * 180.0 / (math.pi * EARTH_RADIUS_EQUA * scale) lat = 360.0 * math.atan(math.exp(my / (EARTH_RADIUS_EQUA * scale))) / math.pi - 90.0 z = location.z return {'lat': lat, 'lon': lon, 'z': z} def location_route_to_gps(route, lat_ref, lon_ref): """ Locate each waypoint of the route into gps, (lat long ) representations. :param route: :param lat_ref: :param lon_ref: :return: """ gps_route = [] for transform, connection in route: gps_point = _location_to_gps(lat_ref, lon_ref, transform.location) gps_route.append((gps_point, connection)) return gps_route def _get_latlon_ref(world): """ Convert from waypoints world coordinates to CARLA GPS coordinates :return: tuple with lat and lon coordinates """ xodr = world.get_map().to_opendrive() tree = ET.ElementTree(ET.fromstring(xodr)) # default reference lat_ref = 42.0 lon_ref = 2.0 for opendrive in tree.iter("OpenDRIVE"): for header in opendrive.iter("header"): for georef in header.iter("geoReference"): if georef.text: str_list = georef.text.split(' ') for item in str_list: if '+lat_0' in item: lat_ref = float(item.split('=')[1]) if '+lon_0' in item: lon_ref = float(item.split('=')[1]) return lat_ref, lon_ref def downsample_route(route, sample_factor): """ Downsample the route by some factor. :param route: the trajectory , has to contain the waypoints and the road options :param sample_factor: Maximum distance between samples :return: returns the ids of the final route that can """ ids_to_sample = [] prev_option = None dist = 0 for i, point in enumerate(route): curr_option = point[1] # Lane changing if curr_option in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT): ids_to_sample.append(i) dist = 0 # When road option changes elif prev_option != curr_option and prev_option not in (RoadOption.CHANGELANELEFT, RoadOption.CHANGELANERIGHT): ids_to_sample.append(i) dist = 0 # After a certain max distance elif dist > sample_factor: ids_to_sample.append(i) dist = 0 # At the end elif i == len(route) - 1: ids_to_sample.append(i) dist = 0 # Compute the distance traveled else: curr_location = point[0].location prev_location = route[i - 1][0].location dist += curr_location.distance(prev_location) prev_option = curr_option return ids_to_sample def interpolate_trajectory(world, waypoints_trajectory, hop_resolution=1.0): """ Given some raw keypoints interpolate a full dense trajectory to be used by the user. :param world: an reference to the CARLA world so we can use the planner :param waypoints_trajectory: the current coarse trajectory :param hop_resolution: is the resolution, how dense is the provided trajectory going to be made :return: the full interpolated route both in GPS coordinates and also in its original form. """ dao = GlobalRoutePlannerDAO(world.get_map(), hop_resolution) grp = GlobalRoutePlanner(dao) grp.setup() # Obtain route plan route = [] for i in range(len(waypoints_trajectory) - 1): # Goes until the one before the last. waypoint = waypoints_trajectory[i] waypoint_next = waypoints_trajectory[i + 1] interpolated_trace = grp.trace_route(waypoint, waypoint_next) for wp_tuple in interpolated_trace: route.append((wp_tuple[0].transform, wp_tuple[1])) # Increase the route position to avoid fails lat_ref, lon_ref = _get_latlon_ref(world) return location_route_to_gps(route, lat_ref, lon_ref), route ================================================ FILE: scenario_runner/srunner/tools/route_parser.py ================================================ #!/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 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 #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') 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 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 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 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 # T 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.LEFT == tuple_wp_turn[1]: subtype = 'S7left' elif RoadOption.RIGHT == tuple_wp_turn[1]: subtype = 'S7right' elif 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 ================================================ FILE: scenario_runner/srunner/tools/scenario_helper.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ Summary of useful helper functions for scenarios """ import math import shapely.geometry import shapely.affinity import numpy as np import carla from agents.tools.misc import vector from agents.navigation.local_planner import RoadOption from srunner.scenariomanager.carla_data_provider import CarlaDataProvider def get_distance_along_route(route, target_location): """ Calculate the distance of the given location along the route Note: If the location is not along the route, the route length will be returned """ wmap = CarlaDataProvider.get_map() covered_distance = 0 prev_position = None found = False # Don't use the input location, use the corresponding wp as location target_location_from_wp = wmap.get_waypoint(target_location).transform.location for position, _ in route: location = target_location_from_wp # Don't perform any calculations for the first route point if not prev_position: prev_position = position continue # Calculate distance between previous and current route point interval_length_squared = ((prev_position.x - position.x) ** 2) + ((prev_position.y - position.y) ** 2) distance_squared = ((location.x - prev_position.x) ** 2) + ((location.y - prev_position.y) ** 2) # Close to the current position? Stop calculation if distance_squared < 0.01: break if distance_squared < 400 and not distance_squared < interval_length_squared: # Check if a neighbor lane is closer to the route # Do this only in a close distance to correct route interval, otherwise the computation load is too high starting_wp = wmap.get_waypoint(location) wp = starting_wp.get_left_lane() while wp is not None: new_location = wp.transform.location new_distance_squared = ((new_location.x - prev_position.x) ** 2) + ( (new_location.y - prev_position.y) ** 2) if np.sign(starting_wp.lane_id) != np.sign(wp.lane_id): break if new_distance_squared < distance_squared: distance_squared = new_distance_squared location = new_location else: break wp = wp.get_left_lane() wp = starting_wp.get_right_lane() while wp is not None: new_location = wp.transform.location new_distance_squared = ((new_location.x - prev_position.x) ** 2) + ( (new_location.y - prev_position.y) ** 2) if np.sign(starting_wp.lane_id) != np.sign(wp.lane_id): break if new_distance_squared < distance_squared: distance_squared = new_distance_squared location = new_location else: break wp = wp.get_right_lane() if distance_squared < interval_length_squared: # The location could be inside the current route interval, if route/lane ids match # Note: This assumes a sufficiently small route interval # An alternative is to compare orientations, however, this also does not work for # long route intervals curr_wp = wmap.get_waypoint(position) prev_wp = wmap.get_waypoint(prev_position) wp = wmap.get_waypoint(location) if prev_wp and curr_wp and wp: if wp.road_id == prev_wp.road_id or wp.road_id == curr_wp.road_id: # Roads match, now compare the sign of the lane ids if (np.sign(wp.lane_id) == np.sign(prev_wp.lane_id) or np.sign(wp.lane_id) == np.sign(curr_wp.lane_id)): # The location is within the current route interval covered_distance += math.sqrt(distance_squared) found = True break covered_distance += math.sqrt(interval_length_squared) prev_position = position return covered_distance, found def get_crossing_point(actor): """ Get the next crossing point location in front of the ego vehicle @return point of crossing """ wp_cross = CarlaDataProvider.get_map().get_waypoint(actor.get_location()) while not wp_cross.is_intersection: wp_cross = wp_cross.next(2)[0] crossing = carla.Location(x=wp_cross.transform.location.x, y=wp_cross.transform.location.y, z=wp_cross.transform.location.z) return crossing def get_geometric_linear_intersection(ego_actor, other_actor): """ Obtain a intersection point between two actor's location by using their waypoints (wp) @return point of intersection of the two vehicles """ wp_ego_1 = CarlaDataProvider.get_map().get_waypoint(ego_actor.get_location()) wp_ego_2 = wp_ego_1.next(1)[0] x_ego_1 = wp_ego_1.transform.location.x y_ego_1 = wp_ego_1.transform.location.y x_ego_2 = wp_ego_2.transform.location.x y_ego_2 = wp_ego_2.transform.location.y wp_other_1 = CarlaDataProvider.get_world().get_map().get_waypoint(other_actor.get_location()) wp_other_2 = wp_other_1.next(1)[0] x_other_1 = wp_other_1.transform.location.x y_other_1 = wp_other_1.transform.location.y x_other_2 = wp_other_2.transform.location.x y_other_2 = wp_other_2.transform.location.y s = np.vstack([(x_ego_1, y_ego_1), (x_ego_2, y_ego_2), (x_other_1, y_other_1), (x_other_2, y_other_2)]) h = np.hstack((s, np.ones((4, 1)))) line1 = np.cross(h[0], h[1]) line2 = np.cross(h[2], h[3]) x, y, z = np.cross(line1, line2) if z == 0: return (float('inf'), float('inf')) intersection = carla.Location(x=x / z, y=y / z, z=0) return intersection def get_location_in_distance(actor, distance): """ Obtain a location in a given distance from the current actor's location. Note: Search is stopped on first intersection. @return obtained location and the traveled distance """ waypoint = CarlaDataProvider.get_map().get_waypoint(actor.get_location()) traveled_distance = 0 while not waypoint.is_intersection and traveled_distance < distance: waypoint_new = waypoint.next(1.0)[-1] traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location) waypoint = waypoint_new return waypoint.transform.location, traveled_distance def get_location_in_distance_from_wp(waypoint, distance, stop_at_junction=True): """ Obtain a location in a given distance from the current actor's location. Note: Search is stopped on first intersection. @return obtained location and the traveled distance """ traveled_distance = 0 while not (waypoint.is_intersection and stop_at_junction) and traveled_distance < distance: wp_next = waypoint.next(1.0) if wp_next: waypoint_new = wp_next[-1] traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location) waypoint = waypoint_new else: break return waypoint.transform.location, traveled_distance def get_waypoint_in_distance(waypoint, distance): """ Obtain a waypoint in a given distance from the current actor's location. Note: Search is stopped on first intersection. @return obtained waypoint and the traveled distance """ traveled_distance = 0 while not waypoint.is_intersection and traveled_distance < distance: waypoint_new = waypoint.next(1.0)[-1] traveled_distance += waypoint_new.transform.location.distance(waypoint.transform.location) waypoint = waypoint_new return waypoint, traveled_distance def generate_target_waypoint_list(waypoint, turn=0): """ This method follow waypoints to a junction and choose path based on turn input. Turn input: LEFT -> -1, RIGHT -> 1, STRAIGHT -> 0 @returns a waypoint list from the starting point to the end point according to turn input """ reached_junction = False threshold = math.radians(0.1) plan = [] while True: wp_choice = waypoint.next(2) if len(wp_choice) > 1: reached_junction = True waypoint = choose_at_junction(waypoint, wp_choice, turn) else: waypoint = wp_choice[0] plan.append((waypoint, RoadOption.LANEFOLLOW)) # End condition for the behavior if turn != 0 and reached_junction and len(plan) >= 3: v_1 = vector( plan[-2][0].transform.location, plan[-1][0].transform.location) v_2 = vector( plan[-3][0].transform.location, plan[-2][0].transform.location) angle_wp = math.acos( np.dot(v_1, v_2) / abs((np.linalg.norm(v_1) * np.linalg.norm(v_2)))) if angle_wp < threshold: break elif reached_junction and not plan[-1][0].is_intersection: break return plan, plan[-1][0] def generate_target_waypoint_list_multilane(waypoint, change='left', distance_same_lane=10, distance_other_lane=25, total_lane_change_distance=25, check='true'): """ This methods generates a waypoint list which leads the vehicle to a parallel lane. The change input must be 'left' or 'right', depending on which lane you want to change. The step distance between waypoints on the same lane is 2m. The step distance between the lane change is set to 25m. @returns a waypoint list from the starting point to the end point on a right or left parallel lane. """ plan = [] plan.append((waypoint, RoadOption.LANEFOLLOW)) # start position step_distance = 2 # check if lane change possible if check == 'true': lane_change_possibilities = ['Left', 'Right', 'Both'] if str(waypoint.lane_change) not in lane_change_possibilities: # ERROR, lane change is not possible return None # same lane distance = 0 while distance < distance_same_lane: next_wp = plan[-1][0].next(step_distance) distance += next_wp[0].transform.location.distance(plan[-1][0].transform.location) plan.append((next_wp[0], RoadOption.LANEFOLLOW)) target_lane_id = None if change == 'left': # go left wp_left = plan[-1][0].get_left_lane() target_lane_id = wp_left.lane_id next_wp = wp_left.next(total_lane_change_distance) plan.append((next_wp[0], RoadOption.LANEFOLLOW)) elif change == 'right': # go right wp_right = plan[-1][0].get_right_lane() target_lane_id = wp_right.lane_id next_wp = wp_right.next(total_lane_change_distance) plan.append((next_wp[0], RoadOption.LANEFOLLOW)) else: # ERROR, input value for change must be 'left' or 'right' return None # other lane distance = 0 while distance < distance_other_lane: next_wp = plan[-1][0].next(step_distance) distance += next_wp[0].transform.location.distance(plan[-1][0].transform.location) plan.append((next_wp[0], RoadOption.LANEFOLLOW)) return plan, target_lane_id def generate_target_waypoint(waypoint, turn=0): """ This method follow waypoints to a junction and choose path based on turn input. Turn input: LEFT -> -1, RIGHT -> 1, STRAIGHT -> 0 @returns a waypoint list according to turn input """ sampling_radius = 1 reached_junction = False wp_list = [] while True: wp_choice = waypoint.next(sampling_radius) # Choose path at intersection if not reached_junction and (len(wp_choice) > 1 or wp_choice[0].is_junction): reached_junction = True waypoint = choose_at_junction(waypoint, wp_choice, turn) else: waypoint = wp_choice[0] wp_list.append(waypoint) # End condition for the behavior if reached_junction and not wp_list[-1].is_junction: break return wp_list[-1] def generate_target_waypoint_in_route(waypoint, route): """ This method follow waypoints to a junction @returns a waypoint list according to turn input """ wmap = CarlaDataProvider.get_map() reached_junction = False # Get the route location shortest_distance = float('inf') for index, route_pos in enumerate(route): wp = route_pos[0] trigger_location = waypoint.transform.location dist_to_route = trigger_location.distance(wp) if dist_to_route <= shortest_distance: closest_index = index shortest_distance = dist_to_route route_location = route[closest_index][0] index = closest_index while True: # Get the next route location index = min(index + 1, len(route)) route_location = route[index][0] road_option = route[index][1] # Enter the junction if not reached_junction and (road_option in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)): reached_junction = True # End condition for the behavior, at the end of the junction if reached_junction and (road_option not in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)): break return wmap.get_waypoint(route_location) def choose_at_junction(current_waypoint, next_choices, direction=0): """ This function chooses the appropriate waypoint from next_choices based on direction """ current_transform = current_waypoint.transform current_location = current_transform.location projected_location = current_location + \ carla.Location( x=math.cos(math.radians(current_transform.rotation.yaw)), y=math.sin(math.radians(current_transform.rotation.yaw))) current_vector = vector(current_location, projected_location) cross_list = [] cross_to_waypoint = dict() for waypoint in next_choices: waypoint = waypoint.next(10)[0] select_vector = vector(current_location, waypoint.transform.location) cross = np.cross(current_vector, select_vector)[2] cross_list.append(cross) cross_to_waypoint[cross] = waypoint select_cross = None if direction > 0: select_cross = max(cross_list) elif direction < 0: select_cross = min(cross_list) else: select_cross = min(cross_list, key=abs) return cross_to_waypoint[select_cross] def get_intersection(ego_actor, other_actor): """ Obtain a intersection point between two actor's location @return the intersection location """ waypoint = CarlaDataProvider.get_map().get_waypoint(ego_actor.get_location()) waypoint_other = CarlaDataProvider.get_map().get_waypoint(other_actor.get_location()) max_dist = float("inf") distance = float("inf") while distance <= max_dist: max_dist = distance current_location = waypoint.transform.location waypoint_choice = waypoint.next(1) # Select the straighter path at intersection if len(waypoint_choice) > 1: max_dot = -1 * float('inf') loc_projection = current_location + carla.Location( x=math.cos(math.radians(waypoint.transform.rotation.yaw)), y=math.sin(math.radians(waypoint.transform.rotation.yaw))) v_current = vector(current_location, loc_projection) for wp_select in waypoint_choice: v_select = vector(current_location, wp_select.transform.location) dot_select = np.dot(v_current, v_select) if dot_select > max_dot: max_dot = dot_select waypoint = wp_select else: waypoint = waypoint_choice[0] distance = current_location.distance(waypoint_other.transform.location) return current_location def detect_lane_obstacle(actor, extension_factor=3, margin=1.02): """ This function identifies if an obstacle is present in front of the reference actor """ world = CarlaDataProvider.get_world() world_actors = world.get_actors().filter('vehicle.*') actor_bbox = actor.bounding_box actor_transform = actor.get_transform() actor_location = actor_transform.location actor_vector = actor_transform.rotation.get_forward_vector() actor_vector = np.array([actor_vector.x, actor_vector.y]) actor_vector = actor_vector / np.linalg.norm(actor_vector) actor_vector = actor_vector * (extension_factor - 1) * actor_bbox.extent.x actor_location = actor_location + carla.Location(actor_vector[0], actor_vector[1]) actor_yaw = actor_transform.rotation.yaw is_hazard = False for adversary in world_actors: if adversary.id != actor.id and \ actor_transform.location.distance(adversary.get_location()) < 50: adversary_bbox = adversary.bounding_box adversary_transform = adversary.get_transform() adversary_loc = adversary_transform.location adversary_yaw = adversary_transform.rotation.yaw overlap_adversary = RotatedRectangle( adversary_loc.x, adversary_loc.y, 2 * margin * adversary_bbox.extent.x, 2 * margin * adversary_bbox.extent.y, adversary_yaw) overlap_actor = RotatedRectangle( actor_location.x, actor_location.y, 2 * margin * actor_bbox.extent.x * extension_factor, 2 * margin * actor_bbox.extent.y, actor_yaw) overlap_area = overlap_adversary.intersection(overlap_actor).area if overlap_area > 0: is_hazard = True break return is_hazard class RotatedRectangle(object): """ This class contains method to draw rectangle and find intersection point. """ def __init__(self, c_x, c_y, width, height, angle): self.c_x = c_x self.c_y = c_y self.w = width # pylint: disable=invalid-name self.h = height # pylint: disable=invalid-name self.angle = angle def get_contour(self): """ create contour """ w = self.w h = self.h c = shapely.geometry.box(-w / 2.0, -h / 2.0, w / 2.0, h / 2.0) rc = shapely.affinity.rotate(c, self.angle) return shapely.affinity.translate(rc, self.c_x, self.c_y) def intersection(self, other): """ Obtain a intersection point between two contour. """ return self.get_contour().intersection(other.get_contour()) ================================================ FILE: scenario_runner/srunner/tools/scenario_parser.py ================================================ #!/usr/bin/env python # Copyright (c) 2019 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ This module provides access to a scenario configuration parser """ import glob import os import xml.etree.ElementTree as ET from srunner.scenarioconfigs.scenario_configuration import ScenarioConfiguration, ActorConfigurationData from srunner.scenarioconfigs.route_scenario_configuration import RouteConfiguration class ScenarioConfigurationParser(object): """ Pure static class providing access to parser methods for scenario configuration files (*.xml) """ @staticmethod def parse_scenario_configuration(scenario_name, config_file_name): """ Parse all scenario configuration files at srunner/examples and the additional config files, providing a list of ScenarioConfigurations @return If scenario_name starts with "group:" all scenarios that have that type are parsed and returned. Otherwise only the scenario that matches the scenario_name is parsed and returned. """ list_of_config_files = glob.glob("{}/srunner/examples/*.xml".format(os.getenv('SCENARIO_RUNNER_ROOT', "./"))) if config_file_name != '': list_of_config_files.append(config_file_name) single_scenario_only = True if scenario_name.startswith("group:"): single_scenario_only = False scenario_name = scenario_name[6:] scenario_configurations = [] for file_name in list_of_config_files: tree = ET.parse(file_name) for scenario in tree.iter("scenario"): scenario_config_name = scenario.attrib.get('name', None) scenario_config_type = scenario.attrib.get('type', None) if single_scenario_only: # Check the scenario is the correct one if scenario_config_name != scenario_name: continue else: # Check the scenario is of the correct type if scenario_config_type != scenario_name: continue new_config = ScenarioConfiguration() new_config.town = scenario.attrib.get('town', None) new_config.name = scenario_config_name new_config.type = scenario_config_type new_config.other_actors = [] new_config.ego_vehicles = [] new_config.trigger_points = [] for weather in scenario.iter("weather"): new_config.weather.cloudiness = float(weather.attrib.get("cloudiness", 0)) new_config.weather.precipitation = float(weather.attrib.get("precipitation", 0)) new_config.weather.precipitation_deposits = float(weather.attrib.get("precipitation_deposits", 0)) new_config.weather.wind_intensity = float(weather.attrib.get("wind_intensity", 0.35)) new_config.weather.sun_azimuth_angle = float(weather.attrib.get("sun_azimuth_angle", 0.0)) new_config.weather.sun_altitude_angle = float(weather.attrib.get("sun_altitude_angle", 15.0)) new_config.weather.fog_density = float(weather.attrib.get("fog_density", 0.0)) new_config.weather.fog_distance = float(weather.attrib.get("fog_distance", 0.0)) new_config.weather.wetness = float(weather.attrib.get("wetness", 0.0)) for ego_vehicle in scenario.iter("ego_vehicle"): new_config.ego_vehicles.append(ActorConfigurationData.parse_from_node(ego_vehicle, 'hero')) new_config.trigger_points.append(new_config.ego_vehicles[-1].transform) for route in scenario.iter("route"): route_conf = RouteConfiguration() route_conf.parse_xml(route) new_config.route = route_conf for other_actor in scenario.iter("other_actor"): new_config.other_actors.append(ActorConfigurationData.parse_from_node(other_actor, 'scenario')) scenario_configurations.append(new_config) return scenario_configurations @staticmethod def get_list_of_scenarios(config_file_name): """ Parse *all* config files and provide a list with all scenarios @return """ list_of_config_files = glob.glob("{}/srunner/examples/*.xml".format(os.getenv('SCENARIO_RUNNER_ROOT', "./"))) list_of_config_files += glob.glob("{}/srunner/examples/*.xosc".format(os.getenv('SCENARIO_RUNNER_ROOT', "./"))) if config_file_name != '': list_of_config_files.append(config_file_name) scenarios = [] for file_name in list_of_config_files: if ".xosc" in file_name: tree = ET.parse(file_name) scenarios.append("{} (OpenSCENARIO)".format(tree.find("FileHeader").attrib.get('description', None))) else: tree = ET.parse(file_name) for scenario in tree.iter("scenario"): scenarios.append(scenario.attrib.get('name', None)) return scenarios ================================================ FILE: scenario_runner/srunner/utilities/code_check_and_formatting.sh ================================================ #!/bin/bash autopep8 scenario_runner.py --in-place --max-line-length=120 autopep8 srunner/scenariomanager/*.py --in-place --max-line-length=120 autopep8 srunner/scenariomanager/actorcontrols/*.py --in-place --max-line-length=120 autopep8 srunner/scenariomanager/scenarioatomics/*.py --in-place --max-line-length=120 autopep8 srunner/scenarios/*.py --in-place --max-line-length=120 autopep8 srunner/autoagents/*.py --in-place --max-line-length=120 autopep8 srunner/tools/*.py --in-place --max-line-length=120 autopep8 srunner/scenarioconfigs/*.py --in-place --max-line-length=120 pylint --rcfile=.pylintrc --disable=I srunner/scenariomanager/ pylint --rcfile=.pylintrc srunner/scenarios/ pylint --rcfile=.pylintrc srunner/autoagents/ pylint --rcfile=.pylintrc srunner/tools/ pylint --rcfile=.pylintrc srunner/scenarioconfigs/ pylint --rcfile=.pylintrc scenario_runner.py